Skip to content

ROS 2 API for sensing data

The robot has various onboard sensor systems by which it observes its whereabouts and the environment in which it is operating. Results of these onboard sensors are, sometimes after filtering, published by the robot to be exploited for navigation typed applications.

Sensing data topics

The topics related to the onboard sensors are summarized in the table below. A more details account per topic is presented later on this page.

Topic Format Type Function
/robot/tf tf2_msgs/msg/TFMessage publisher Information obout the robot's tf-tree
/robot/joint_states sensor_msgs/JointState publisher Information on wheel states
/robot/odom nav_msgs/Odometry publisher 2D position, velocity, orientation and angular velocity of the robot after filtering the IMU and wheel encoders of the robot
/robot/gnss/fix sensor_msgs/NavSatFix publisher GNSS fix information
/robot/gnss/status origin_msgs/GNSSStatus publisher GNSS status information
/robot/initial_heading origin_msgs/InitialHeading publisher Initial heading at startup
/robot/camera/color/camera_info sensor_msgs/CameraInfo publisher Information about the camera characterstics
/robot/camera/color/image_raw sensor_msgs/Image publisher RGB image of the realsense camera of the robot
/robot/camera/color/meta_data realsense2_camera_msgs/MetaData publisher JSON string of the realsense settings
/robot/camera/depth/camera_info sensor_msgs/CameraInfo publisher Information about the camera characterstics
/robot/camera/depth/image_raw sensor_msgs/Image publisher depth image of the realsense camera of the robot
/robot/camera/depth/meta_data realsense2_camera_msgs/MetaData publisher JSON string of the realsense settings
/robot/lidar/points sensor_msgs/PointCloud2 publisher 3D pointcloud of the Ouster LiDAR (if available)

Transforms

The topic /robot/tf has the following characteristics:
    Message type: tf2_msgs/msg/TFMessage
    Published transforms
        odom->base_link
            Frequency: 25Hz
            Data: pose, twist
            Comment: Same transform as /robot/odom
         map->odom
            Frequency: 25Hz
            Data: pose, twist
            Comment: Same transform as /robot/pose_fused

Joint states

The topic /robot/joint_states has the following characteristics:
    Message type: sensor_msgs/JointState
    Frame: ${parent_link}_${prefix}_wheel (e.g. main_body_left_rear_joint_wheel)
    Frequency: 1Hz and on change
    Data: position, velocity, effort
Information on the state of the wheels, including wheel position [radians], velocity [radians per second] and motor effort [Nm] is the motor torque determined from the measured motor current and the motor torque constant.

Odometery

The topic /robot/odom has the following characteristics:
    Message type: nav_msgs/Odometry
    Frame: odom & base_link
    Frequency: 25Hz
    Data: pose, twist, covariances
Content of the message contains the output of a 2D EKF that uses the IMU and the wheel encoders as its inputs. The covariance estimate is updated each time step as part of the EKF algorithm. Note that the EKF only updates when movement is detected (i.e., moving wheels) to prevent drifting over time.

GNSS(-RTK)

Info

GNSS related topics output no data if no GNSS add-on is purchased/mounted.

The topic /robot/gnss/fix has the following characteristics:
    Message type: sensor_msgs/NavSatFix
    Frame: gps_link
    Frequency: 1Hz and on change
    Data: latitude, longitude, height, position covariance, fix status
Sends an updated fix if a new GNSS location is available or every second if no new value is provided. Latitude, longitude and height are just forwarded from the Simulink U-blox driver. Position covariance is calculated from the horizontal (x, y) and vertical accuracy (z) by squaring them to get the respective variances. The status field (or fix type) is mapped as follows:

fix status Meaning
0 No fix.
1 No fix and dead reckoning only.
2 2D RTK fix.
3 3D RTK fix.
4 GNSS fix with dead reckoning.
5 No fix and time only.

The topic /robot/gnss/status has the following characteristics:
    Message type: origin_msgs/GNSSStatus
    Frame: gps_link
    Frequency: 1Hz and on change
    Data: RTK fix status, position accuracy, number of satellites in view, number of satellites used
Contains information on the GNSS horizontal and vertical position accuracy, number of satellites visible and number of satellites used. Also contains GNSS status:

GNSS status Meaning
-2 Unknown status
-1 No fix
0 2D fix, no RTK base station used
1 3D fix, no RTK base station used
2 RTK fix with floating ambiguity, multiple solution possible
3 RTK fix with fixed ambiguity, single solution, highest accuracy

Initial heading (magnetometer)

The topic /robot/initial_heading has the following characteristics:
    Message type: origin_msgs/InitialHeading
    Frame: n/a
    Frequency: 1Hz and on change
    Data: initial heading
The initial heading of the Origin with respect to magnetic North in radians determined at boot time. Note that the accuracy of this heading estimate is heavily influenced by magnetic disturbances in the environment and/or changes in the magnetic field. If the Origin is used at a location far from where the calibration was performed (Eindhoven by default), it is recommended to perform a new magnetometer calibration procedure.

Camera (RealSense)

The topics /robot/camera/color/camera_info and /robot/camera/depth/camera_info have the following characteristics:
    Message type: sensor_msgs/CameraInfo
    Frame: n/a
    Frequency: 6 FPS
    Data: image height, image width, distortion and parameters of the camera's intrinsic matrix, rectification matrix and projection matrix,

The topics /robot/camera/color/image_raw and /robot/camera/depth/image_raw have the following characteristics:
    Message type: sensor_msgs/Image
    Frame: camera_link
    Frequency: 6 FPS
    Data: image height, image width, encoding and actual image data,

The topics /robot/camera/color/meta_data and /robot/camera/depth/meta_data have the following characteristics:
    Message type: realsense2_camera_msgs/MetaData
    Frame: n/a
    Frequency: 6 FPS
    Data: json
The metadata messages store the camera's available metadata in a json format. To learn more, a dedicated script for echoing a metadata topic in runtime is attached. For instance, use the following command to echo the camera/depth/metadata topic:
python3 src/realsense-ros/realsense2_camera/scripts/echo_metadata.py /camera/camera/depth/metadata