Sensory Information


Sensory information encompasses data such as SLAM, camera imagery, calibration, IMU, and ToF. In subsequent secondary development, these interfaces can be used to acquire and invoke data.


Visual Odometry(VO)

Function Overview: Obtain a rapid 60Hz pose.
Topic: perception/visual_slam/tracking/vo_pose
Msg Type s-e: geometry_msgs/msg/PoseStamped

SLAM Odometry

Function Overview: Odometry that integrates IMU and has undergone pose optimization.
Topic: perception/visual_slam/tracking/Odometry
Msg Type s-e: nav_msgs/msg/Odometry

Pose Reset

Function Overview: Reset the odometry to zero.
Topic: perception/visual_slam/reset
Msg Type s-e: visual_slam/reset
Code Example: ros2 service call /visual_slam/reset tita_perception_msgs/srv/Reset

Camera Sensor Data

Function Overview: Publish undistorted color images from the camera at 60Hz.
Topic:
perception/sensor/camera/left
perception/sensor/camera/right
Msg Type s-e: sensor_msgs/msg/Image

Camera Calibration Data

Function Overview: Publish camera calibration data at a frequency of 60Hz.
Topic:
perception/sensor/camera_info/left
perception/sensor/camera_info/right
Msg Type s-e: sensor_msgs/msg/CameraInfo

Camera Point Cloud Data

Function Overview: Camera-estimated depth data, colored point cloud. Contains < 140,544 points, Point cloud distance ≤ 5 meters.
Topic: perception/sensor/camera/point_cloud
Msg Type s-e: sensor_msgs/msg/PointCloud2

Camera IMU Data

Function Overview: Camera IMU data includes acceleration, angular velocity, and posture.
Topic: perception/sensor/camera/imu
Msg Type s-e: sensor_msgs/msg/Imu

Front Face ToF Data

Function Overview: Front-facing ToF (Time-of-Flight) converted point cloud data. 8x8.
Topic: perception/sensor/spad/face/point
Msg Type s-e: sensor_msgs/msg/PointCloud2

Lower ToF Data

Function Overview: Lower ToF converted point cloud data. 8x8.
Topic: perception/sensor/spad/neck/point
Msg Type s-e: sensor_msgs/msg/PointCloud2

Robot Joint Coordinate System

Function Overview: Synchronize joint coordinates.
Topic: perception/wheel/tracking/odometry
Msg Type s-e: tf2_msgs/msg/TFMessage

Wheeled Odometry

Function Overview: Short-range odometry. Unable to record Z-axis information.
Topic: perception/wheel/tracking/odometry
Msg Type s-e:nav_msgs/msg/Odometry

Slope Detection

Function Overview: Based on the area that is 50 cm to one meter ahead and as wide as the robot.
Topic:perception/sensor/camera/attention_region
Msg Type s-e:sensor_msgs/msg/PointCloud2

ToF-based Staircase Detection and Identification Point Cloud

Function Overview: Each set of four points represents a step. There are a total of eight points.
Topic:perception/spad/stair/point_cloud
Msg Type s-e:sensor_msgs/msg/PointCloud2

Step Distance Recognition

Function Overview: The distance from the steps to the robot’s base_link is calculated based on the recognized points.
Topic:perception/spad/stair/distance
Msg Type s-e:std_msgs/msg/Float

Slope Angle Detection

Function Overview: Angle feedback of the slope detection area.
Topic:perception/sensor/camera/attention_region/angle
Msg Type s-e:std_msgs/msg/Float