diff --git a/mujoco_ros/CHANGELOG.md b/mujoco_ros/CHANGELOG.md index 9dac3139..4b86f298 100644 --- a/mujoco_ros/CHANGELOG.md +++ b/mujoco_ros/CHANGELOG.md @@ -14,6 +14,8 @@ * replaced `boost::shared_ptr` with `std::shared_ptr` or `std::unique_ptr` wherever possible (ROS 1 fast intra-process message-passing requires boost::shared_ptr). * replaced `shared_ptr` with `unique_ptr` wherever possible. * replaced smart pointer constructor initialization with `make_shared` or `make_unique` wherever possible. +* Updated to MuJoCo library version 2.3.7. +* * Added [jointactuatorfrc](https://mujoco.readthedocs.io/en/2.3.7/XMLreference.html#sensor-jointactuatorfrc) support in `mujoco_ros_sensors`. Contributors: @DavidPL1, @acodeodyssey @@ -48,7 +50,7 @@ Contributors: @DavidPL1, @LeroyR, @rhaschke ### Added * Updated to MuJoCo library version 2.3.6. -* Added a `step(num_steps=1, blocking=true)` public function./ +* Added a `step(num_steps=1, blocking=true)` public function. * Unit tests for plugin loading and resetting and running callbacks correctly. * Now automatically building with AVX instructions, if possible. * CMake tooling borrowed from deepminds MuJoCo repo and https://github.com/osjacky430/ros_pkg_template/. diff --git a/mujoco_ros/CMakeLists.txt b/mujoco_ros/CMakeLists.txt index e6c5001b..6bba83c7 100644 --- a/mujoco_ros/CMakeLists.txt +++ b/mujoco_ros/CMakeLists.txt @@ -58,7 +58,7 @@ configure_project_option( ) # Find MuJoCo -find_package(mujoco 2.3.6 REQUIRED) +find_package(mujoco 2.3.7 REQUIRED) find_library(GLFW libglfw.so.3) # ############################################### diff --git a/mujoco_ros_sensors/src/mujoco_sensor_handler_plugin.cpp b/mujoco_ros_sensors/src/mujoco_sensor_handler_plugin.cpp index 0a524a55..1b94a906 100644 --- a/mujoco_ros_sensors/src/mujoco_sensor_handler_plugin.cpp +++ b/mujoco_ros_sensors/src/mujoco_sensor_handler_plugin.cpp @@ -84,6 +84,7 @@ bool MujocoRosSensorsPlugin::load(const mjModel *model, mjData *data) SENSOR_STRING[mjSENS_ACTUATORFRC] = "actuatorfrc"; SENSOR_STRING[mjSENS_BALLQUAT] = "ballquat"; SENSOR_STRING[mjSENS_BALLANGVEL] = "ballangvel"; + SENSOR_STRING[mjSENS_JOINTACTFRC] = "jointactfrc"; SENSOR_STRING[mjSENS_JOINTLIMITPOS] = "jointlimitpos"; SENSOR_STRING[mjSENS_JOINTLIMITVEL] = "jointlimitvel"; SENSOR_STRING[mjSENS_JOINTLIMITFRC] = "jointlimitfrc"; @@ -335,6 +336,7 @@ void MujocoRosSensorsPlugin::lastStageCallback(const mjModel *model, mjData *dat case mjSENS_ACTUATORPOS: case mjSENS_ACTUATORVEL: case mjSENS_ACTUATORFRC: + case mjSENS_JOINTACTFRC: case mjSENS_JOINTLIMITPOS: case mjSENS_JOINTLIMITVEL: case mjSENS_JOINTLIMITFRC: @@ -572,6 +574,7 @@ void MujocoRosSensorsPlugin::initSensors(const mjModel *model, mjData *data) case mjSENS_ACTUATORPOS: case mjSENS_ACTUATORVEL: case mjSENS_ACTUATORFRC: + case mjSENS_JOINTACTFRC: case mjSENS_JOINTLIMITPOS: case mjSENS_JOINTLIMITVEL: case mjSENS_JOINTLIMITFRC: