Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
24 changes: 24 additions & 0 deletions include/mujoco_ros2_simulation/mujoco_system_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,30 @@ class MujocoSystemInterface : public hardware_interface::SystemInterface
hardware_interface::return_type read(const rclcpp::Time& time, const rclcpp::Duration& period) override;
hardware_interface::return_type write(const rclcpp::Time& time, const rclcpp::Duration& period) override;

/**
* @brief Returns a copy of the MuJoCo model.
*
* This method locks the simulation mutex to ensure thread safety.
* @param dest Pointer to an mjModel structure where the copy will be stored. The pointer will be allocated if it is nullptr.
*/
void get_model(mjModel*& dest);

/**
* @brief Returns a copy of the current MuJoCo data.
*
* This method locks the simulation mutex to ensure thread safety.
* @param dest Pointer to an mjData structure where the copy will be stored. The pointer will be allocated if it is nullptr.
*/
void get_data(mjData*& dest);

/**
* @brief Sets the MuJoCo data to the provided value.
*
* This method locks the simulation mutex to ensure thread safety.
* @param mj_data Pointer to an mjData structure containing the new data.
*/
void set_data(mjData* mj_data);

private:
/**
* @brief Loads actuator information into the HW interface.
Expand Down
22 changes: 22 additions & 0 deletions src/mujoco_system_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1223,6 +1223,28 @@ void MujocoSystemInterface::publish_clock()
clock_publisher_->publish(sim_time_msg);
}

void MujocoSystemInterface::get_model(mjModel*& dest)
{
const std::unique_lock<std::recursive_mutex> lock(*sim_mutex_);
dest = mj_copyModel(dest, mj_model_);
}

void MujocoSystemInterface::get_data(mjData*& dest)
{
const std::unique_lock<std::recursive_mutex> lock(*sim_mutex_);
if (dest == nullptr)
{
dest = mj_makeData(mj_model_);
}
mj_copyData(dest, mj_model_, mj_data_);
}

void MujocoSystemInterface::set_data(mjData* mj_data)
{
const std::unique_lock<std::recursive_mutex> lock(*sim_mutex_);
mj_copyData(mj_data_, mj_model_, mj_data);
}

} // namespace mujoco_ros2_simulation

#include "pluginlib/class_list_macros.hpp"
Expand Down
Loading