4. Topics
The following listed topics are available, depending for which robot you launched the bridge. Note that the topics differ between NAO and Pepper, since they don’t have the same sensor and actuators (e.g. 3D camera). Further, this list may vary over time, since the bridge is still actively under development.
4.1. Main topics
Camera Front
/<robot-prefix>/camera/front/camera_info (sensor_msgs/CameraInfo): publishes information on the front camera /<robot-prefix>/camera/front/image_raw (sensor_msgs/Image): publish the images of the Top Camera obtained from ALVideoDevice
Camera Depth (Pepper only)
/<robot-prefix>/camera/depth/camera_info (sensor_msgs/CameraInfo): publishes information on the depth camera /<robot-prefix>/camera/depth/image_raw (sensor_msgs/Image): publish the depth images obtained from ALVideoDevice
IMU
/<robot-prefix>/imu_base (sensor_msgs/Imu): publishes the IMU of Pepper base(Pepper only) /<robot-prefix>/imu_torso (sensor_msgs/Imu): publishes the IMU of the robot’s torso
Joint States
/joint_states (sensor_msgs/JointState): uses the keys named Device/SubDeviceList/*/Position/Sensor/Value at a frequency of 15Hz.
Laser
/<robot-prefix>/laser (sensor_msgs/LaserScan): publishes the obstacles’ positions retrieved through lasers.
Sonar
/<robot-prefix>/sonar/left (sensor_msgs/Range): publishes the left sonar values of Nao (Nao only) /<robot-prefix>/sonar/right (sensor_msgs/Range): publishes the right sonar values of Nao (Nao only) /<robot-prefix>/sonar/front (sensor_msgs/Range): publishes the front sonar values of Pepper (Pepper only) /<robot-prefix>/sonar/back (sensor_msgs/Range): publishes the back sonar values of Pepepr (Pepper only)
TF
/tf (tf2_msgs/TFMessage): the usual tf message, using /joint_states
Go back to the index.