slamware_ros_sdk_server_node Node

The slamware_ros_sdk_server_node connects to the Aurora-based spatial mapping device, publishing the device's map, pose, and status information, and receiving commands to control the device..

1. Subscribed Topics

sync_map (slamware_ros_sdk/SyncMapRequest)

Synchronize the map

clear_map (slamware_ros_sdk/ClearMapRequest)

Clear the map

set_map_update (slamware_ros_sdk/SetMapUpdateRequest)

Set the map update switch status

set_map_localization (slamware_ros_sdk/SetMapLocalizationRequest)

Set the localization switch status

relocalization_cancel (slamware_ros_sdk/RelocalizationCancelRequest)

Cancel relocalization

2. Published Topics

scan (sensor_msgs/LaserScan)

LiDAR data, published at a fixed frequency(only available when an external LiDAR is connected)

robot_pose(geometry_msgs/PoseStamped)

Robot pose information, published at a fixed frequency

map_metadata (nav_msgs/MapMetaData)

Basic map information (including resolution, size, origin), published at a fixed frequency

map(nav_msgs/OccupancyGrid)

Map data, published at a fixed frequency

system_status (slamware_ros_sdk/SystemStatus)

Publish system status

relocalization_status (slamware_ros_sdk/RelocalizationStatus)

Relocalization status, published at a fixed frequency

left_image_raw (sensor_msgs/Image)

Left camera image, published at a fixed frequency

right_image_raw (sensor_msgs/Image)

Right camera image, published at a fixed frequency

stereo_keypoints (sensor_msgs/Image)

Image with key points, published at a fixed frequency

imu_raw_data (sensor_msgs/Imu)

IMU accelerometer and gyroscope data, published at a fixed frequency

point_cloud (sensor_msgs/PointCloud2)

Point cloud data, published at a fixed frequency

3. Services

sync_get_stcm (slamware_ros_sdk/SyncGetStcm)

Fetch maps in stcm format

sync_set_stcm (slamware_ros_sdk/SyncSetStcm)

Replace maps with specified stcm file

relocalization (slamware_ros_sdk/RelocalizationRequest)

Request relocalization

4. Parameters

Parameter Type Default Description
ip_address string "192.168.11.1" IP address for connecting to the robot
robot_port int 1445 Port for connecting to the robot
reconn_wait_ms uint 3000 Reconnection wait time in milliseconds
angle_compensate bool true Angle compensation switch
robot_frame string "base_link" Robot base reference frame
laser_frame string "laser" Laser reference frame
map_frame string "map" Map reference frame
imu_frame string "imu_link" IMU reference frame
camera_left string "camera_left" Left camera reference frame
camera_right string "camera_right" Right camera reference frame
robot_pose_pub_period float 0.05 Robot pose publishing period (seconds)
scan_pub_period float 0.1 LiDAR data publishing period (seconds)
map_update_period float 0.2 Map update period (seconds)
map_pub_period float 0.2 Map data publishing period (seconds)
map_sync_once_get_max_wh float 100.0 Maximum size for map synchronization
map_update_near_robot_half_wh float 8.0 Map update size centered around the robot
imu_raw_data_period float 0.05 IMU raw data publishing period (seconds)
event_period float 1.0 Event detection period for map setup/loop closure (seconds)
system_status_pub_period float 0.05 System status publishing period (seconds)
stereo_image_pub_period float 0.067 Image publishing period (seconds)
point_cloud_pub_period float 0.1 Point cloud publishing period (seconds)
depth_image_pub_period float 0.067 Depth image publishing period (seconds)
odom_pub_period float 0.05 Odometry publishing period (seconds)
scan_topic string "/slamware_ros_sdk_server_node/scan" LiDAR data publishing topic
robot_pose_topic string "/slamware_ros_sdk_server_node/robot_pose" Robot pose publishing topic
map_topic string "/slamware_ros_sdk_server_node/map" Map publishing topic
map_info_topic string "/slamware_ros_sdk_server_node/map_metadata" Map metadata publishing topic
imu_raw_data_topic string "/slamware_ros_sdk_server_node/imu_raw_data" IMU accelerometer and gyroscope publishing topic
system_status_topic_name string "/slamware_ros_sdk_server_node/system_status" System status publishing topic
relocalization_status_topic_name string "/slamware_ros_sdk_server_node/relocalization_status" Relocalization status publishing topic
left_image_raw_topic_name string "/slamware_ros_sdk_server_node/left_image_raw" Left camera image publishing topic
right_image_raw_topic_name string "/slamware_ros_sdk_server_node/right_image_raw" Right camera image publishing topic
point_cloud_topic_name string "/slamware_ros_sdk_server_node/point_cloud" Point cloud publishing topic
stereo_keypoints_topic_name string "/slamware_ros_sdk_server_node/stereo_keypoints" Stereo feature extraction publishing topic
depth_image_raw_topic_name string "/slamware_ros_sdk_server_node/depth_image_raw" Depth camera raw image publishing topic
depth_image_colorized_topic_name string "/slamware_ros_sdk_server_node/depth_image_colorized" Depth camera colorized image publishing topic
semantic_segmentation_topic_name string "/slamware_ros_sdk_server_node/semantic_segmentation" Semantic segmentation colorized image publishing topic
odom_topic_name string "/slamware_ros_sdk_server_node/odom" Odometry publishing topic

5. Required tf Transforms

None

6. Provided tf Transforms

laser -> map

Pose of LIDAR scan in the map(only available when an external LiDAR is connected)

base_link -> laser

Static transform from base link to laser frame(only available when an external LiDAR is connected)

camera_left-> base_link

Static transform from left camera to base link

camera_right-> camera_left

Static transform from right camera to left camera

imu_link -> camera_left

Static transform from IMU frame to left camera