File tree Expand file tree Collapse file tree 2 files changed +46
-0
lines changed
include/mujoco_ros2_simulation Expand file tree Collapse file tree 2 files changed +46
-0
lines changed Original file line number Diff line number Diff line change @@ -73,6 +73,30 @@ class MujocoSystemInterface : public hardware_interface::SystemInterface
7373 hardware_interface::return_type read (const rclcpp::Time& time, const rclcpp::Duration& period) override ;
7474 hardware_interface::return_type write (const rclcpp::Time& time, const rclcpp::Duration& period) override ;
7575
76+ /* *
77+ * @brief Returns a copy of the MuJoCo model.
78+ *
79+ * This method locks the simulation mutex to ensure thread safety.
80+ * @param dest Pointer to an mjModel structure where the copy will be stored. The pointer will be allocated if it is nullptr.
81+ */
82+ void get_model (mjModel*& dest);
83+
84+ /* *
85+ * @brief Returns a copy of the current MuJoCo data.
86+ *
87+ * This method locks the simulation mutex to ensure thread safety.
88+ * @param dest Pointer to an mjData structure where the copy will be stored. The pointer will be allocated if it is nullptr.
89+ */
90+ void get_data (mjData*& dest);
91+
92+ /* *
93+ * @brief Sets the MuJoCo data to the provided value.
94+ *
95+ * This method locks the simulation mutex to ensure thread safety.
96+ * @param mj_data Pointer to an mjData structure containing the new data.
97+ */
98+ void set_data (mjData* mj_data);
99+
76100private:
77101 /* *
78102 * @brief Loads actuator information into the HW interface.
Original file line number Diff line number Diff line change @@ -1328,6 +1328,28 @@ void MujocoSystemInterface::publish_clock()
13281328 clock_publisher_->publish (sim_time_msg);
13291329}
13301330
1331+ void MujocoSystemInterface::get_model (mjModel*& dest)
1332+ {
1333+ const std::unique_lock<std::recursive_mutex> lock (*sim_mutex_);
1334+ dest = mj_copyModel (dest, mj_model_);
1335+ }
1336+
1337+ void MujocoSystemInterface::get_data (mjData*& dest)
1338+ {
1339+ const std::unique_lock<std::recursive_mutex> lock (*sim_mutex_);
1340+ if (dest == nullptr )
1341+ {
1342+ dest = mj_makeData (mj_model_);
1343+ }
1344+ mj_copyData (dest, mj_model_, mj_data_);
1345+ }
1346+
1347+ void MujocoSystemInterface::set_data (mjData* mj_data)
1348+ {
1349+ const std::unique_lock<std::recursive_mutex> lock (*sim_mutex_);
1350+ mj_copyData (mj_data_, mj_model_, mj_data);
1351+ }
1352+
13311353} // namespace mujoco_ros2_simulation
13321354
13331355#include " pluginlib/class_list_macros.hpp"
You can’t perform that action at this time.
0 commit comments