@@ -108,9 +108,10 @@ It is the same executable and parameters as the upstream, but requires updating
108108 )
109109```
110110
111- > ** _ NOTE_ ** : We can remove the the ROS 2 control node after the next ros2_control upstream release,
112- as the simulation requires [ this PR] ( https://github.com/ros-controls/ros2_control/pull/2654 ) to run.
113- The hardware interface _ should_ then be compatible with ` humble ` , ` jazzy ` , and ` kilted ` .
111+ > [ !NOTE]
112+ > We can remove the the ROS 2 control node after the next ros2_control upstream release,
113+ > as the simulation requires [ this PR] ( https://github.com/ros-controls/ros2_control/pull/2654 ) to run.
114+ > The hardware interface _ should_ then be compatible with ` humble ` , ` jazzy ` , and ` kilted ` .
114115
115116### Joints
116117
@@ -347,7 +348,8 @@ The lidar sensor is then configurable through ROS 2 control xacro with:
347348
348349This project includes a [ compose] ( ./docker-compose.yml ) and [ Dockerfile] ( ./.docker/Dockerfile ) for development and testing in an isolated environment.
349350
350- ** Note** : you may need to give docker access to xhost with ` xhost +local:docker ` to ensure the container has access to the host UI.
351+ > [ !NOTE]
352+ > You may need to give docker access to xhost with ` xhost +local:docker ` to ensure the container has access to the host UI.
351353
352354For users on arm64 machines, be sure to specify the ` CPU_ARCH ` variable in your environment when building.
353355
@@ -377,7 +379,9 @@ ${MUJOCO_DIR}/bin/simulate ${ROS_WS}/src/mujoco_ros2_simulation/test/test_resour
377379ros2 launch mujoco_ros2_simulation test_robot.launch.py
378380```
379381
380- > ** _ NOTE:_ ** Rendering contexts in containers can be tricky.
382+ > [ !NOTE]
383+ > Rendering contexts in containers can be tricky.
384+
381385Users may need to tweak the compose file to support their specific host OS or GPUs.
382386For more information refer to the comments in the compose file.
383387
@@ -424,3 +428,8 @@ From there, command joints to move with,
424428``` bash
425429ros2 topic pub /position_controller/commands std_msgs/msg/Float64MultiArray " data: [-0.25, 0.75]" --once
426430```
431+
432+ > [ !TIP]
433+ > UI panels can be toggled with ` Tab ` or ` Shift+Tab ` .
434+ > All standard MuJoCo keyboard shortcuts are available.
435+ > To see a short list, press ` F1 ` .
0 commit comments