This document introduces the SLAMWARE ROS SDK.


Content



Get Started

Download and install SDK

Please visit Support and Download section at Slamtec official website to download proper ROS SDK and extract it to your disk.

Directory Structure

Slamware ROS SDK is composed of resources and codes might be required in the development of Slamware and ROS based applications, and organized as following:

DirectoryDescription
docsReference documents
srcSource code
--slamware_ros_sdkSource code of Slamware ROS SDK
--slamware_sdkHeaders and libraries of Slamware C++ SDK

Development Environment

  • Ubuntu 16.04 amd64
  • ROS packages

Hardware Requirements

A Slamware-based mobile robot is required to use Slamware ROS SDK. It should be switched on and configured with proper IP address, which will be connected to from the slamware_ros_sdk_server_node ROS node.



Hello World

1.Create workspace

Put source code directory src into an empty workspace. Eg. catkin_ws, use catkin utility to initialize workspace.

cd catkin_ws/src
catkin_init_workspace

2.Compile

cd ..catkin_make

3.Setup workspace environment

source devel/setup.bash

4.Start Node

Please connect to the WiFi hot spot provided by the mobile robot if it is configured in AP mode, and start ROS node:

roslaunch slamware_ros_sdk slamware_ros_sdk_server_node.launch ip_address:=192.168.11.1

View by rviz:

roslaunch slamware_ros_sdk view_slamware_ros_sdk_server_node.launch



Nodes

NodeComments
slamware_ros_sdk_server_node NodePublish maps, robot pose and status, receives control commands



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

slamware_ros_sdk/SyncMapRequest
File
slamware_ros_sdk/msg/SyncMapRequest.msg

Definition

None


set_pose (geometry_msgs/Pose)

Set current pose of the robot


recover_localization (slamware_ros_sdk/RecoverLocalizationRequest)

Trigger relocalization operation of the robot

slamware_ros_sdk/RecoverLocalizationRequest

File

slamware_ros_sdk/msg/RecoverLocalizationRequest.msg

Definition  
FieldData type Comments 
area slamware_ros_sdk/RectFlt32Search area
options slamware_ros_sdk/LocalizationOptionsRelocalization options
slamware_ros_sdk/RectFlt32
File

slamware_ros_sdk/msg/RectFlt32.msg

Definition
FieldData typeComments
xfloat32x of origin
yfloat32y of origin
wfloat32width
hfloat32height
slamware_ros_sdk/LocalizationOptions
File

slamware_ros_sdk/msg/LocalizationOptions.msg

Definition
FieldData type描述
max_time_msslamware_ros_sdk/OptionalInt32Timeout of relocalization (in ms)
mvmt_typeslamware_ros_sdk/OptionalLocalizationMovementBehaviour of relocalization
slamware_ros_sdk/OptionalInt32
File

slamware_ros_sdk/msg/OptionalInt32.msg

Definition
FieldData typeComments
is_validboolis the value valid
valueint32value

slamware_ros_sdk/OptionalLocalizationMovement

File

slamware_ros_sdk/msg/OptionalLocalizationMovement.msg

Definition
FieldData typeComments
is_validboolis the value valid
valueslamware_ros_sdk/LocalizationMovementRelocalization behaviour
slamware_ros_sdk/LocalizationMovement
File

slamware_ros_sdk/msg/LocalizationMovement.msg

Definition
FieldData typeComments
typeint8Unknown=-1, Static=0, Rotation only=1, Any movement=2

clear_map (slamware_ros_sdk/ClearMapRequest)

Clear current built map

slamware_ros_sdk/ClearMapRequest

File

slamware_ros_sdk/msg/ClearMapRequest.msg

Definition
FieldData typeComments
kindslamware_ros_sdk/MapKindMap kind
slamware_ros_sdk/MapKind
File

slamware_ros_sdk/msg/MapKind.msg

Definition
FieldData typeComments
kindint8Unknown=-1, EXPLORERMAP=0, ...

set_map_update (slamware_ros_sdk/SetMapUpdateRequest)

Enable or disable map update

slamware_ros_sdk/SetMapUpdateRequest

 File
 slamware_ros_sdk/msg/SetMapUpdateRequest.msg
Definition
FieldData typeComments
 enabledbool  Enable of disable map update
 kindslamware_ros_sdk/MapKind  Map kind
slamware_ros_sdk/MapKind
File

slamware_ros_sdk/msg/MapKind.msg

Definition
FieldData typeComments
kindint8Unknown=-1,EXPLORERMAP=0,...

set_map_localization (slamware_ros_sdk/SetMapLocalizationRequest)

Enable or disable localization

slamware_ros_sdk/SetMapLocalizationRequest

File
 slamware_ros_sdk/msg/SetMapLocalizationRequest.msg
Definition
FieldData typeComments
 enabledbool Enable or disable map localization 

move_by_direction (slamware_ros_sdk/MoveByDirectionRequest)

Manually control robot to move by direction

slamware_ros_sdk/MoveByDirectionRequest

File
 slamware_ros_sdk/msg/MoveByDirectionRequest.msg
Definition
FieldData typeComments
 direction slamware_ros_sdk/ActionDirection Direction of movement
 options slamware_ros_sdk/MoveOptions Options of movements
slamware_ros_sdk/ActionDirection
File
 slamware_ros_sdk/msg/ActionDirection.msg
Definition
FieldData typeComments
 direction int8 Unknown=-1, Forward=0, Backward=1, Turn Right=2, Turn Left=3

slamware_ros_sdk/MoveOptions

File
 slamware_ros_sdk/msg/MoveOptions.msg
Definition
FieldData typeComments
 opt_flags slamware_ros_sdk/MoveOptionFlagMove options
 speed_ratio slamware_ros_sdk/OptionalFlt64

Max speed limit ratio

slamware_ros_sdk/MoveOptionFlag
File
 slamware_ros_sdk/msg/MoveOptionFlag.msg
Definition
FieldData typeComments
flagsuint32Flag options
Enumeration
EnumerationValueComments
 NONE 0x00000000 No option
 APPENDING 0x00000001Append the goal to current goal queue, or replace the whole goal queue
 MILESTONE 0x00000002Deprecated
 NO_SMOOTH 0x00000004Do not smooth the path
 KEY_POINTS 0x00000008Move via virtual tracks
 PRECISE 0x00000010Move to goal precisely
 WITH_YAW 0x00000020Turn to specific heading when reached target location
 RETURN_UNREACHABLE_DIRECTLY 0x00000040If the goal is occupied, return unreachable directly, or find a nearby place as alternative goal
 KEY_POINTS_WITH_OA 0x00000080Move with virtual-track-priority mode
slamware_ros_sdk/OptionalFlt64
File
 slamware_ros_sdk/msg/OptionalFlt64.msg
Definition
FieldData typeComments
is_validboolis the value valid
 value float64value

move_by_theta (slamware_ros_sdk/MoveByThetaRequest)

Manually control robot to move by track ball

slamware_ros_sdk/MoveByThetaRequest
File
slamware_ros_sdk/msg/MoveByThetaRequest.msg
Definition
FieldData typeComments
 theta float32Direction of track ball
 options slamware_ros_sdk/MoveOptionsMovement options

slamware_ros_sdk/MoveOptions

File
 slamware_ros_sdk/msg/MoveOptions.msg
Definition
FieldData typeComments
 opt_flags slamware_ros_sdk/MoveOptionFlagMove options
 speed_ratio slamware_ros_sdk/OptionalFlt64

Max speed limit ratio

slamware_ros_sdk/MoveOptionFlag
File
 slamware_ros_sdk/msg/MoveOptionFlag.msg
Definition
FieldData typeComments
flagsuint32Flag options
Enumeration
EnumerationValueComments
 NONE 0x00000000 No option
 APPENDING 0x00000001Append the goal to current goal queue, or replace the whole goal queue
 MILESTONE 0x00000002Deprecated
 NO_SMOOTH 0x00000004Do not smooth the path
 KEY_POINTS 0x00000008Move via virtual tracks
 PRECISE 0x00000010Move to goal precisely
 WITH_YAW 0x00000020Turn to specific heading when reached target location
 RETURN_UNREACHABLE_DIRECTLY 0x00000040If the goal is occupied, return unreachable directly, or find a nearby place as alternative goal
 KEY_POINTS_WITH_OA 0x00000080Move with virtual-track-priority mode
slamware_ros_sdk/OptionalFlt64
File
 slamware_ros_sdk/msg/OptionalFlt64.msg
Definition
FieldData typeComments
is_validboolis the value valid
 value float64value


move_to (slamware_ros_sdk/MoveToRequest)

Request autonomous navigation to specific goal, and heading

slamware_ros_sdk/MoveToRequest
File
 slamware_ros_sdk/msg/MoveToRequest.msg
Definition
FieldData typeComments
 location geometry_msgs/PointThe goal location
 options slamware_ros_sdk/MoveOptionsMove options
 yaw float32Ending robot heading

slamware_ros_sdk/MoveOptions

File
 slamware_ros_sdk/msg/MoveOptions.msg
Definition
FieldData typeComments
 opt_flags slamware_ros_sdk/MoveOptionFlagMove options
 speed_ratio slamware_ros_sdk/OptionalFlt64

Max speed limit ratio

slamware_ros_sdk/MoveOptionFlag
File
 slamware_ros_sdk/msg/MoveOptionFlag.msg
Definition
FieldData typeComments
flagsuint32Flag options
Enumeration
EnumerationValueComments
 NONE 0x00000000 No option
 APPENDING 0x00000001Append the goal to current goal queue, or replace the whole goal queue
 MILESTONE 0x00000002Deprecated
 NO_SMOOTH 0x00000004Do not smooth the path
 KEY_POINTS 0x00000008Move via virtual tracks
 PRECISE 0x00000010Move to goal precisely
 WITH_YAW 0x00000020Turn to specific heading when reached target location
 RETURN_UNREACHABLE_DIRECTLY 0x00000040If the goal is occupied, return unreachable directly, or find a nearby place as alternative goal
 KEY_POINTS_WITH_OA 0x00000080Move with virtual-track-priority mode
slamware_ros_sdk/OptionalFlt64
File
 slamware_ros_sdk/msg/OptionalFlt64.msg
Definition
FieldData typeComments
is_validboolis the value valid
 value float64value


move_to_locations (slamware_ros_sdk/MoveToLocationsRequest)

Request autonomous navigation to a series of goals

slamware_ros_sdk/MoveToLocationsRequest
File
 slamware_ros_sdk/msg/MoveToLocationsRequest.msg
Definition
FieldData typeComments
 locations geometry_msgs/Point[]The goal location
 options slamware_ros_sdk/MoveOptionsMove options
 yaw float32Ending robot heading

slamware_ros_sdk/MoveOptions

File
 slamware_ros_sdk/msg/MoveOptions.msg
Definition
FieldData typeComments
 opt_flags slamware_ros_sdk/MoveOptionFlagMove options
 speed_ratio slamware_ros_sdk/OptionalFlt64

Max speed limit ratio

slamware_ros_sdk/MoveOptionFlag
File
 slamware_ros_sdk/msg/MoveOptionFlag.msg
Definition
FieldData typeComments
flagsuint32Flag options
Enumeration
EnumerationValueComments
 NONE 0x00000000 No option
 APPENDING 0x00000001Append the goal to current goal queue, or replace the whole goal queue
 MILESTONE 0x00000002Deprecated
 NO_SMOOTH 0x00000004Do not smooth the path
 KEY_POINTS 0x00000008Move via virtual tracks
 PRECISE 0x00000010Move to goal precisely
 WITH_YAW 0x00000020Turn to specific heading when reached target location
 RETURN_UNREACHABLE_DIRECTLY 0x00000040If the goal is occupied, return unreachable directly, or find a nearby place as alternative goal
 KEY_POINTS_WITH_OA 0x00000080Move with virtual-track-priority mode
slamware_ros_sdk/OptionalFlt64
File
 slamware_ros_sdk/msg/OptionalFlt64.msg
Definition
FieldData typeComments
is_validboolis the value valid
 value float64value


rotate_to (slamware_ros_sdk/RotateToRequest)

Request rotation to specific heading

slamware_ros_sdk/RotateToRequest
File
 slamware_ros_sdk/msg/RotateToRequest.msg
Definition
FieldData typeComments
 orientation geometry_msgs/QuaternionSpecifying the orientation
 options slamware_ros_sdk/MoveOptionsMove options

slamware_ros_sdk/MoveOptions

File
 slamware_ros_sdk/msg/MoveOptions.msg
Definition
FieldData typeComments
 opt_flags slamware_ros_sdk/MoveOptionFlagMove options
 speed_ratio slamware_ros_sdk/OptionalFlt64

Max speed limit ratio

slamware_ros_sdk/MoveOptionFlag
File
 slamware_ros_sdk/msg/MoveOptionFlag.msg
Definition
FieldData typeComments
flagsuint32Flag options
Enumeration
EnumerationValueComments
 NONE 0x00000000 No option
 APPENDING 0x00000001Append the goal to current goal queue, or replace the whole goal queue
 MILESTONE 0x00000002Deprecated
 NO_SMOOTH 0x00000004Do not smooth the path
 KEY_POINTS 0x00000008Move via virtual tracks
 PRECISE 0x00000010Move to goal precisely
 WITH_YAW 0x00000020Turn to specific heading when reached target location
 RETURN_UNREACHABLE_DIRECTLY 0x00000040If the goal is occupied, return unreachable directly, or find a nearby place as alternative goal
 KEY_POINTS_WITH_OA 0x00000080Move with virtual-track-priority mode
slamware_ros_sdk/OptionalFlt64
File
 slamware_ros_sdk/msg/OptionalFlt64.msg
Definition
FieldData typeComments
is_validboolis the value valid
 value float64value


rotate (slamware_ros_sdk/RotateRequest)

Request rotation by specific angle

slamware_ros_sdk/RotateRequest
File
 slamware_ros_sdk/msg/RotateRequest.msg
Definition
FieldData typeComments
 orientation geometry_msgs/QuaternionSpecifying the rotation
 options slamware_ros_sdk/MoveOptionsMove options

slamware_ros_sdk/MoveOptions

File
 slamware_ros_sdk/msg/MoveOptions.msg
Definition
FieldData typeComments
 opt_flags slamware_ros_sdk/MoveOptionFlagMove options
 speed_ratio slamware_ros_sdk/OptionalFlt64

Max speed limit ratio

slamware_ros_sdk/MoveOptionFlag
File
 slamware_ros_sdk/msg/MoveOptionFlag.msg
Definition
FieldData typeComments
flagsuint32Flag options
Enumeration
EnumerationValueComments
 NONE 0x00000000 No option
 APPENDING 0x00000001Append the goal to current goal queue, or replace the whole goal queue
 MILESTONE 0x00000002Deprecated
 NO_SMOOTH 0x00000004Do not smooth the path
 KEY_POINTS 0x00000008Move via virtual tracks
 PRECISE 0x00000010Move to goal precisely
 WITH_YAW 0x00000020Turn to specific heading when reached target location
 RETURN_UNREACHABLE_DIRECTLY 0x00000040If the goal is occupied, return unreachable directly, or find a nearby place as alternative goal
 KEY_POINTS_WITH_OA 0x00000080Move with virtual-track-priority mode
slamware_ros_sdk/OptionalFlt64
File
 slamware_ros_sdk/msg/OptionalFlt64.msg
Definition
FieldData typeComments
is_validboolis the value valid
 value float64value


go_home (slamware_ros_sdk/GoHomeRequest)

Request robot to go back to the charge station

slamware_ros_sdk/GoHomeRequest
File

slamware_ros_sdk/msg/GoHomeRequest.msg

Definition
None

cancel_action (slamware_ros_sdk/CancelActionRequest)

Abort current movement action

slamware_ros_sdk/CancelActionRequest
File
slamware_ros_sdk/msg/CancelActionRequest.msg
Definition
None

add_line (slamware_ros_sdk/AddLineRequest)

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

slamware_ros_sdk/AddLineRequest

File
 slamware_ros_sdk/msg/AddLineRequest.msg
Definition
FieldData typeComments
usage  slamware_ros_sdk/ArtifactUsage Line type
 line slamware_ros_sdk/Line2DFlt32 Line position

slamware_ros_sdk/ArtifactUsage

File
 slamware_ros_sdk/msg/ArtifactUsage.msg
Definition
FieldData typeComments
 usage int8 Unknown=-1, Virtual Walls=0, Virtual Tracks=1
slamware_ros_sdk/Line2DFlt32
File
 slamware_ros_sdk/msg/Line2DFlt32.msg
Definition
FieldData typeComments
 id uint32Line segment id
 start slamware_ros_sdk/Vec2DFlt32Start point of line segment
 end slamware_ros_sdk/Vec2DFlt32End point of line segment
slamware_ros_sdk/Vec2DFlt32
File
 slamware_ros_sdk/msg/Vec2DFlt32.msg
Definition
FieldData typeComments
xfloat32x
yfloat32y

add_lines (slamware_ros_sdk/AddLinesRequest)

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

slamware_ros_sdk/AddLinesRequest

File
 slamware_ros_sdk/msg/AddLinesRequest.msg
Definition
FieldData typeComments
usage  slamware_ros_sdk/ArtifactUsageLine type
 line slamware_ros_sdk/Line2DFlt32[]Positions of lines

slamware_ros_sdk/ArtifactUsage

File
 slamware_ros_sdk/msg/ArtifactUsage.msg
Definition
FieldData typeComments
 usage int8Unknown=-1, Virtual Walls=0, Virtual Tracks=1
slamware_ros_sdk/Line2DFlt32
File
 slamware_ros_sdk/msg/Line2DFlt32.msg
Definition
FieldData typeComments
 id uint32Line segment id
 start slamware_ros_sdk/Vec2DFlt32Start point of line segment
 end slamware_ros_sdk/Vec2DFlt32End point of line segment
slamware_ros_sdk/Vec2DFlt32
File
 slamware_ros_sdk/msg/Vec2DFlt32.msg
Definition
FieldData typeComments
xfloat32x
yfloat32y


remove_line (slamware_ros_sdk/RemoveLineRequest)

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

slamware_ros_sdk/RemoveLineRequest
File
 slamware_ros_sdk/msg/RemoveLineRequest.msg
Definition
FieldData typeComments
 usage slamware_ros_sdk/ArtifactUsageLine type
id uint32Line segment id

slamware_ros_sdk/ArtifactUsage

File
 slamware_ros_sdk/msg/ArtifactUsage.msg
Definition
FieldData typeComments
 usage int8Unknown=-1, Virtual Walls=0, Virtual Tracks=1

clear_lines (slamware_ros_sdk/ClearLinesRequest)

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

slamware_ros_sdk/ClearLinesRequest
File
 slamware_ros_sdk/msg/ClearLinesRequest.msg
Definition
FieldData typeComments
 usageslamware_ros_sdk/ArtifactUsage Line segment type

slamware_ros_sdk/ArtifactUsage

File
 slamware_ros_sdk/msg/ArtifactUsage.msg
Definition
FieldData typeComments
 usage int8Unknown=-1, Virtual Walls=0, Virtual Tracks=1

move_line (slamware_ros_sdk/MoveLineRequest)

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

slamware_ros_sdk/MoveLineRequest
File
 slamware_ros_sdk/msg/MoveLineRequest.msg
Definition
FieldData typeComments
 usage slamware_ros_sdk/ArtifactUsage Line segment type
 line slamware_ros_sdk/Line2DFlt32New position of line segments

slamware_ros_sdk/ArtifactUsage

File
 slamware_ros_sdk/msg/ArtifactUsage.msg
Definition
FieldData typeComments
 usage int8Unknown=-1, Virtual Walls=0, Virtual Tracks=1
slamware_ros_sdk/Line2DFlt32
File
 slamware_ros_sdk/msg/Line2DFlt32.msg
Definition
FieldData typeComments
 id uint32Line segment id
 start slamware_ros_sdk/Vec2DFlt32Start point of line segment
 end slamware_ros_sdk/Vec2DFlt32End point of line segment
slamware_ros_sdk/Vec2DFlt32
File
slamware_ros_sdk/msg/Vec2DFlt32.msg
Definition
FieldData typeComments
xfloat32x
yfloat32y

move_lines (slamware_ros_sdk/MoveLinesRequest)

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

slamware_ros_sdk/MoveLinesRequest
File
slamware_ros_sdk/msg/MoveLinesRequest.msg
Definition
FieldData typeComments
 usage slamware_ros_sdk/ArtifactUsage Line segment type
 line slamware_ros_sdk/Line2DFlt32[]New positions of line segments

slamware_ros_sdk/ArtifactUsage

File
 slamware_ros_sdk/msg/ArtifactUsage.msg
Definition
FieldData typeComments
 usage int8Unknown=-1, Virtual Walls=0, Virtual Tracks=1
slamware_ros_sdk/Line2DFlt32
File
 slamware_ros_sdk/msg/Line2DFlt32.msg
Definition
FieldData typeComments
 id uint32Line segment id
 start slamware_ros_sdk/Vec2DFlt32Start point of line segment
 end slamware_ros_sdk/Vec2DFlt32End point of line segment
slamware_ros_sdk/Vec2DFlt32
File
 slamware_ros_sdk/msg/Vec2DFlt32.msg
Definition
FieldData typeComments
xfloat32x
yfloat32y



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

slamware_ros_sdk/BasicSensorInfoArray
File
 slamware_ros_sdk/msg/BasicSensorInfoArray.msg
Definition
FieldData typeComments
 sensors_info slamware_ros_sdk/BasicSensorInfo[]Sensor information
slamware_ros_sdk/BasicSensorInfo
File
slamware_ros_sdk/msg/BasicSensorInfo.msg
Definition
FieldData typeComments
idint32Sensor ID
sensor_typeslamware_ros_sdk/SensorTypeSensor Type
impact_typeslamware_ros_sdk/ImpactTypeSignal type (digital/analog)
install_posegeometry_msgs/PoseInstallation pose
refresh_freqfloat32Refresh rate
slamware_ros_sdk/SensorType
File
 slamware_ros_sdk/msg/SensorType.msg
Definition
FieldData typeComments
typeint8Unknown=-1, Bumper=0, Cliff=1, Sonar,=2, Depth Camera=3, Wall Following Sensor=4, Meganet Tape=5
slamware_ros_sdk/ImpactType
File
 slamware_ros_sdk/msg/ImpactType.msg
Definition
FieldData typeComments
 type int8Unknown=-1,Digital=0,Analog=1

basic_sensors_values (slamware_ros_sdk/BasicSensorValueDataArray)

Sensor data, updated periodically

slamware_ros_sdk/BasicSensorValueDataArray
File
 slamware_ros_sdk/msg/BasicSensorValueDataArray.msg
Definition
FieldData typeComments
 values_data slamware_ros_sdk/BasicSensorValueData[]Sensor data
slamware_ros_sdk/BasicSensorValueData
File
slamware_ros_sdk/msg/BasicSensorValueData.msg
Definition
FieldData typeComments
info  slamware_ros_sdk/BasicSensorInfoSensor information 
value slamware_ros_sdk/BasicSensorValueSensor value
slamware_ros_sdk/BasicSensorValue
File
slamware_ros_sdk/msg/BasicSensorValue.msg
Definition
FieldData typeComments
is_in_impactboolSensor is activated or not
valuefloat32 Sensor analog value
slamware_ros_sdk/BasicSensorInfo
File
slamware_ros_sdk/msg/BasicSensorInfo.msg
Definition
FieldData typeComments
idint32Sensor ID
sensor_typeslamware_ros_sdk/SensorTypeSensor Type
impact_typeslamware_ros_sdk/ImpactTypeSignal type (digital/analog)
install_posegeometry_msgs/PoseInstallation pose
refresh_freqfloat32Refresh rate
slamware_ros_sdk/SensorType
File
 slamware_ros_sdk/msg/SensorType.msg
Definition
FieldData type Comments
typeint8Unknown=-1, Bumper=0, Cliff=1, Sonar,=2, Depth Camera=3, Wall Following Sensor=4, Meganet Tape=5
slamware_ros_sdk/ImpactType
File
 slamware_ros_sdk/msg/ImpactType.msg
Definition
FieldData typeComments
 type int8Unknown=-1,Digital=0,Analog=1


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

slamware_ros_sdk/RobotBasicState
File
slamware_ros_sdk/msg/RobotBasicState.msg
Definition
FieldData typeComments
 is_map_building_enabledboolMap update is enabled or not
 is_localization_enabledboolLocalization is enabled or not
 localization_qualityint32Localization quality
 board_temperatureint32Motherboard temperature
 battery_percentageint32Battery percentage
 is_dc_inboolIs the DC cord connected
 is_chargingboolIs charging


virtual_walls (slamware_ros_sdk/Line2DFlt32Array)

Virtual walls, updated periodically

slamware_ros_sdk/Line2DFlt32Array
File
slamware_ros_sdk/msg/Line2DFlt32Array.msg
Definition
FieldData typeComments
linesslamware_ros_sdk/Line2DFlt32[]Multiple line segments 
slamware_ros_sdk/Line2DFlt32
File
 slamware_ros_sdk/msg/Line2DFlt32.msg
Definition
FieldData typeComments
 id uint32Line segment id
 start slamware_ros_sdk/Vec2DFlt32Start point of line segment
 end slamware_ros_sdk/Vec2DFlt32End point of line segment
slamware_ros_sdk/Vec2DFlt32
File
 slamware_ros_sdk/msg/Vec2DFlt32.msg
Definition
FieldData typeComments
xfloat32x
yfloat32y


virtual_tracks (slamware_ros_sdk/Line2DFlt32Array)

Virtual tracks, updated periodically

slamware_ros_sdk/Line2DFlt32Array
File
slamware_ros_sdk/msg/Line2DFlt32Array.msg
Definition
FieldData typeComments
linesslamware_ros_sdk/Line2DFlt32[]Multiple line segments
slamware_ros_sdk/Line2DFlt32
File
 slamware_ros_sdk/msg/Line2DFlt32.msg
Definition
FieldData typeComments
 id uint32Line segment id
 start slamware_ros_sdk/Vec2DFlt32Start point of line segment
 end slamware_ros_sdk/Vec2DFlt32End point of line segment
slamware_ros_sdk/Vec2DFlt32
File
 slamware_ros_sdk/msg/Vec2DFlt32.msg
Definition
FieldData typeComments
xfloat32x
yfloat32y



3. Services

sync_get_stcm (slamware_ros_sdk/SyncGetStcm)

Fetch maps in stcm format

slamware_ros_sdk/SyncGetStcm
File
slamware_ros_sdk/srv/SyncGetStcm.srv
Request
None
Response
FieldData typeComments
raw_stcmint8[]stcm map data

sync_set_stcm (slamware_ros_sdk/SyncSetStcm)

Replace maps with specified stcm file

slamware_ros_sdk/SyncSetStcm
File
slamware_ros_sdk/srv/SyncGetStcm.srv
Request
FieldData typeComments
raw_stcmint8[]uploaded stcm map data
robot_posegeometry_msgs/Poseuploaded robot pose
Response
None



4. Parameters

ParameterData typeDefault valueDescription
ip_addressstring"192.168.11.1"The IP address of the robot
robot_portint1445The port of the robot
reconn_wait_msuint3000Time to reconnect, unit: ms
angle_compensatebooltrueAngular compensation switch
fixed_odom_map_tfbooltrueFixed odometry of the robot
robot_framestring"/base_link"Robot base frame name
laser_framestring"/laser"Laser frame name
odom_framestring"/odom"Odometry frame name
map_framestring"/map"Map frame name
robot_pose_pub_periodfloat0.05Period to publish robot pose, unit: seconds
scan_pub_periodfloat0.1Period to publish LIDAR scan, unit: seconds
map_update_periodfloat0.2Period to update map from Slamware, unit: seconds
map_pub_periodfloat0.2Period to publish map, unit: seconds
basic_sensors_info_update_periodfloat7.0Period to update sensor metadata, unit: seconds
basic_sensors_values_pub_periodfloat0.05Period to publish sensor data, unit: seconds
path_pub_periodfloat0.05Period to publish global path, unit: seconds
robot_basic_state_pub_periodfloat1.0Period to publish robot status, unit: seconds
virtual_walls_pub_periodfloat0.5Period to publish virtual walls, unit: seconds
virtual_tracks_pub_periodfloat0.5Period to publish virtual tracks, unit: seconds
map_sync_once_get_max_whfloat100.0Max edge length of map on synchronizing, unit: meters
map_update_near_robot_half_whfloat8.0Partial map update distance, unit: meters
scan_topicstring"scan"Topic to publish LIDAR scan
odom_topicstring"odom"Topic to publish robot pose
map_topicstring"map"Topic to publish map
map_info_topicstring"map_metadata"Topic to publish map metadata
basic_sensors_info_topicstring"basic_sensors_info"Topic to publish sensor metadata
basic_sensors_values_topicstring"basic_sensors_values"Topic to publish sensor values
path_topicstring"global_plan_path"Topic to publish global path
vel_control_topicstring"/cmd_vel"Topic to subscribe manual control commands
goal_topicstring"/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)
  • No labels