slamware_ros_sdk_server_node节点
slamware_ros_sdk_server_node节点连接基于Aurora空间建图设备,发布该设备的地图、位姿与状态信息,并接收指令用于控制设备。
1. 订阅主题
sync_map (slamware_ros_sdk/SyncMapRequest)
地图同步
clear_map (slamware_ros_sdk/ClearMapRequest)
清除地图
set_map_update (slamware_ros_sdk/SetMapUpdateRequest)
设置建图开关状态
set_map_localization (slamware_ros_sdk/SetMapLocalizationRequest)
设置定位开关状态
relocalization_cancel (slamware_ros_sdk/RelocalizationCancelRequest)
取消重定位
2. 发布主题
scan (sensor_msgs/LaserScan)
激光雷达数据,定频发布(仅在外接激光雷达时有效)
robot_pose (geometry_msgs/PoseStamped)
机器人位姿信息,定频发布
map_metadata (nav_msgs/MapMetaData)
地图基本信息(包括分辨率、尺寸、原点位置),定频发布
map (nav_msgs/OccupancyGrid)
地图数据,定频发布(仅在外接激光雷达时有效)
system_status (slamware_ros_sdk/SystemStatus)
发布系统状态
relocalization_status (slamware_ros_sdk/RelocalizationStatus)
重定位状态,定频发布
depth_image_raw (sensor_msgs/Image)
深度相机原始图像,定频发布
depth_image_colorized (sensor_msgs/Image)
深度相机彩色化图像,定频发布
semantic_segmentation (sensor_msgs/Image)
语义分割彩色化图像(可叠加相机预览),定频发布
odom (nav_msgs/Odometry)
里程计信息,定频发布
state (std_msgs/String)
节点与设备连接状态(connected/disconnected),定频发布
left_image_raw (sensor_msgs/Image)
左目图像,定频发布
right_image_raw (sensor_msgs/Image)
右目图像,定频发布
stereo_keypoints (sensor_msgs/Image)
带特征点图像,定频发布
imu_raw_data (sensor_msgs/Imu)
IMU 加速度计和陀螺仪数据,定频发布
point_cloud (sensor_msgs/PointCloud2)
点云数据,定频发布
3. 服务
sync_get_stcm (slamware_ros_sdk/SyncGetStcm)
获取stcm地图
sync_set_stcm (slamware_ros_sdk/SyncSetStcm)
上传stcm地图
relocalization (slamware_ros_sdk/RelocalizationRequest)
请求重定位。
4. 参数
| 参数 | 类型 | 默认 | 描述 |
|---|---|---|---|
| ip_address | string | "192.168.11.1" | 连接机器人的IP地址 |
| robot_port | int | 1445 | 连接机器人的端口 |
| reconn_wait_ms | uint | 3000 | 重连等待时间,单位:毫秒 |
| angle_compensate | bool | true | 角度补偿开关 |
| ladar_data_clockwise | bool | true | 激光数据角度是否顺时针(用于角度补偿) |
| robot_frame | string | "base_link" | 机器人基参考系 |
| laser_frame | string | "laser" | 激光参考系 |
| map_frame | string | "map" | 地图参考系 |
| odom_frame | string | "odom" | 里程计参考系 |
| imu_frame | string | "imu_link" | IMU 参考系 |
| camera_left | string | "camera_left" | 左目参考系 |
| camera_right | string | "camera_right" | 右目参考系 |
| odometry_pub_period | float | 0.1 | 里程计发布周期(秒) |
| robot_pose_pub_period | float | 0.05 | 机器人位姿发布周期(秒) |
| scan_pub_period | float | 0.1 | 激光数据发布周期(秒) |
| map_update_period | float | 0.3 | 地图更新周期(秒) |
| map_pub_period | float | 0.3 | 地图数据发布周期(秒) |
| map_sync_once_get_max_wh | float | 100.0 | 地图同步最大尺寸 |
| map_update_near_robot_half_wh | float | 8.0 | 地图更新以机器人为中心的长宽半尺寸 |
| imu_raw_data_period | float | 0.05 | IMU 原始数据发布周期(秒) |
| event_period | float | 1.0 | 事件检测周期(秒) |
| system_status_pub_period | float | 0.1 | 系统状态发布周期(秒) |
| stereo_image_pub_period | float | 0.1 | 双目图像发布周期(秒) |
| point_cloud_pub_period | float | 0.2 | 点云发布周期(秒) |
| scan_topic | string | "/slamware_ros_sdk_server_node/scan" | 激光数据发布主题 |
| robot_pose_topic | string | "/slamware_ros_sdk_server_node/robot_pose" | 机器人位姿发布主题 |
| odom_topic | string | "/slamware_ros_sdk_server_node/odom" | 里程计发布主题 |
| map_topic | string | "/slamware_ros_sdk_server_node/map" | 地图发布主题 |
| map_info_topic | string | "/slamware_ros_sdk_server_node/map_metadata" | 地图信息发布主题 |
| imu_raw_data_topic | string | "/slamware_ros_sdk_server_node/imu_raw_data" | IMU 加速度计和陀螺仪发布主题 |
| system_status_topic_name | string | "/slamware_ros_sdk_server_node/system_status" | 系统状态发布主题 |
| relocalization_status_topic_name | string | "/slamware_ros_sdk_server_node/relocalization_status" | 重定位状态发布主题 |
| left_image_raw_topic_name | string | "/slamware_ros_sdk_server_node/left_image_raw" | 左目图像发布主题 |
| right_image_raw_topic_name | string | "/slamware_ros_sdk_server_node/right_image_raw" | 右目图像发布主题 |
| point_cloud_topic_name | string | "/slamware_ros_sdk_server_node/point_cloud" | 点云发布主题 |
| stereo_keypoints_topic_name | string | "/slamware_ros_sdk_server_node/stereo_keypoints" | 双目提取特征发布主题 |
| depth_image_raw_topic_name | string | "/slamware_ros_sdk_server_node/depth_image_raw" | 深度相机原始图像发布主题 |
| depth_image_colorized_topic_name | string | "/slamware_ros_sdk_server_node/depth_image_colorized" | 深度相机彩色化图像发布主题 |
| semantic_segmentation_topic_name | string | "/slamware_ros_sdk_server_node/semantic_segmentation" | 语义分割图像发布主题 |
5. 监听tf变换
无
6. 广播tf变换
laser -> map
激光雷达在地图中的位姿(仅在外接激光雷达时有效)
base_link -> laser
baselink到激光坐标系静态变换(仅在外接激光雷达时有效)
camera_left-> base_link
左目到base静态变换
camera_right-> camera_left
右目到左目静态变换
imu_link -> camera_left
imu坐标系到左目静态变换