=================== Topics and Services =================== This section documents all ROS topics and services provided by the DexRobot MuJoCo node. Input Topics ---------- joint_commands ^^^^^^^^^^^^ Control joint positions directly. - **Type**: ``sensor_msgs/JointState`` - **Fields**: - ``name``: List of joint names - ``position``: List of target positions - **Example**: .. code-block:: python from sensor_msgs.msg import JointState msg = JointState() msg.name = ['r_f_joint1_1', 'r_f_joint1_2'] msg.position = [0.5, 0.7] hand_pose ^^^^^^^^ Control 6-DoF floating hand pose. - **Type**: ``geometry_msgs/Pose`` - **Fields**: - ``position``: Position (x, y, z) - ``orientation``: Quaternion (w, x, y, z) - **Notes**: - Must specify ``--hand-pose-topic`` to enable - Position is scaled by ``position_magnifiers`` - **Example**: .. code-block:: python from geometry_msgs.msg import Pose msg = Pose() msg.position.x = 0.5 msg.position.y = 0.0 msg.position.z = 1.0 msg.orientation.w = 1.0 msg.orientation.x = 0.0 msg.orientation.y = 0.0 msg.orientation.z = 0.0 Output Topics ----------- joint_states ^^^^^^^^^^ Current joint positions and velocities. - **Type**: ``sensor_msgs/JointState`` - **Fields**: - ``name``: List of tracked joint names - ``position``: Current joint positions - ``velocity``: Current joint velocities - **Update Rate**: 100Hz (default) body_poses ^^^^^^^^^ 6-DoF poses of tracked bodies. - **Type**: ``geometry_msgs/PoseArray`` - **Fields**: - ``poses``: List of poses for tracked bodies - ``header``: Standard header with timestamp - **Update Rate**: 100Hz (default) touch_sensors ^^^^^^^^^^^ Touch sensor readings from fingertips. - **Type**: ``std_msgs/Float32MultiArray`` - **Fields**: - ``data``: List of force values - **Update Rate**: 100Hz (default) - **Units**: Newtons (N) Services ------- save_screenshot ^^^^^^^^^^^^ Save current viewer frame as image. - **Type**: ``std_srvs/Trigger`` - **Response**: - ``success``: True if screenshot saved - ``message``: File path or error message - **Example**: .. code-block:: bash # ROS2 ros2 service call /save_screenshot std_srvs/srv/Trigger # ROS1 rosservice call /save_screenshot Message Formats ------------- JointState Format ^^^^^^^^^^^^^^^ .. code-block:: yaml header: stamp: