slamware_ros_sdk_server_node Node

slamware_ros_sdk_server_node node connects to Slamware-based robots, publishes maps, poses, status, and receives control commands.

1. Subscribed Topics

/cmd_vel (geometry_msgs/Twist)

Linear and angular speed command to robot

/move_base_simple/goal (geometry_msgs/PoseStamped)

Specify the goal of robot (with yaw control, precise mode)

sync_map (slamware_ros_sdk/SyncMapRequest)

Sync whole map from Slamware

set_pose (geometry_msgs/Pose)

Set current pose of the robot

recover_localization (slamware_ros_sdk/RecoverLocalizationRequest)

Trigger relocalization operation of the robot

clear_map (slamware_ros_sdk/ClearMapRequest)

Clear current built map

set_map_update (slamware_ros_sdk/SetMapUpdateRequest)

Enable or disable map update

set_map_localization (slamware_ros_sdk/SetMapLocalizationRequest)

Enable or disable localization

move_by_direction (slamware_ros_sdk/MoveByDirectionRequest)

Manually control robot to move by direction

move_by_theta (slamware_ros_sdk/MoveByThetaRequest)

Manually control robot to move by track ball

move_to (slamware_ros_sdk/MoveToRequest)

Request autonomous navigation to specific goal, and heading

move_to_locations (slamware_ros_sdk/MoveToLocationsRequest)

Request autonomous navigation to a series of goals

rotate_to (slamware_ros_sdk/RotateToRequest)

Request rotation to specific heading

rotate (slamware_ros_sdk/RotateRequest)

Request rotation by specific angle

go_home (slamware_ros_sdk/GoHomeRequest)

Request robot to go back to the charge station

cancel_action (slamware_ros_sdk/CancelActionRequest)

Abort current movement action

add_line (slamware_ros_sdk/AddLineRequest)

Add a line (virtual wall, virtual track, and etc.)

add_lines (slamware_ros_sdk/AddLinesRequest)

Add multiple lines (virtual wall, virtual track, and etc.)

remove_line (slamware_ros_sdk/RemoveLineRequest)

Remove specific line (virtual wall, virtual track, and etc.)

clear_lines (slamware_ros_sdk/ClearLinesRequest)

Clear all lines (virtual wall, virtual track, and etc.)

move_line (slamware_ros_sdk/MoveLineRequest)

Move specific line (virtual wall, virtual track, and etc.)

move_lines (slamware_ros_sdk/MoveLinesRequest)

Move multiple lines (virtual wall, virtual track, and etc.)

2. Published Topics

scan (sensor_msgs/LaserScan)

LIDAR scan, updated periodically

odom (nav_msgs/Odometry)

Robot pose, updated periodically

map_metadata (nav_msgs/MapMetaData)

Map metadata (resolution, size, origin), updated periodically

map (nav_msgs/OccupancyGrid)

Map data, updated periodically

basic_sensors_info (slamware_ros_sdk/BasicSensorInfoArray)

Sensor metadata (id, type, digital/analog, installation pose, refresh rate), updated on change

basic_sensors_values (slamware_ros_sdk/BasicSensorValueDataArray)

Sensor data, updated periodically

global_plan_path (nav_msgs/Path)

Global planned path, updated periodically

robot_basic_state (slamware_ros_sdk/RobotBasicState)

Robot status (map update switch, localization switch, motherboard temperature, charging status, battery), updated periodically

virtual_walls (slamware_ros_sdk/Line2DFlt32Array)

Virtual walls, updated periodically

virtual_tracks (slamware_ros_sdk/Line2DFlt32Array)

Virtual tracks, updated periodically

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

4. Parameters

Parameter Data type Default value Description
ip_address string "192.168.11.1" The IP address of the robot
robot_port int 1445 The port of the robot
reconn_wait_ms uint 3000 Time to reconnect, unit: ms
angle_compensate bool true Angular compensation switch
fixed_odom_map_tf bool true Fixed odometry of the robot
robot_frame string "/base_link" Robot base frame name
laser_frame string "/laser" Laser frame name
odom_frame string "/odom" Odometry frame name
map_frame string "/map" Map frame name
robot_pose_pub_period float 0.05 Period to publish robot pose, unit: seconds
scan_pub_period float 0.1 Period to publish LIDAR scan, unit: seconds
map_update_period float 0.2 Period to update map from Slamware, unit: seconds
map_pub_period float 0.2 Period to publish map, unit: seconds
basic_sensors_info_update_period float 7.0 Period to update sensor metadata, unit: seconds
basic_sensors_values_pub_period float 0.05 Period to publish sensor data, unit: seconds
path_pub_period float 0.05 Period to publish global path, unit: seconds
robot_basic_state_pub_period float 1.0 Period to publish robot status, unit: seconds
virtual_walls_pub_period float 0.5 Period to publish virtual walls, unit: seconds
virtual_tracks_pub_period float 0.5 Period to publish virtual tracks, unit: seconds
map_sync_once_get_max_wh float 100.0 Max edge length of map on synchronizing, unit: meters
map_update_near_robot_half_wh float 8.0 Partial map update distance, unit: meters
scan_topic string "scan" Topic to publish LIDAR scan
odom_topic string "odom" Topic to publish robot pose
map_topic string "map" Topic to publish map
map_info_topic string "map_metadata" Topic to publish map metadata
basic_sensors_info_topic string "basic_sensors_info" Topic to publish sensor metadata
basic_sensors_values_topic string "basic_sensors_values" Topic to publish sensor values
path_topic string "global_plan_path" Topic to publish global path
vel_control_topic string "/cmd_vel" Topic to subscribe manual control commands
goal_topic string "/move_base_simple/goal" Topic to subscribe autonomous navigation goals

5. Required tf Transforms

None

6. Provided tf Transforms

laser -> map

Pose of LIDAR scan in the map

base_link -> odom

Pose estimation of the robot

odom -> map

Odometry information of the robot (maybe fixed or not provided according to the configuration)