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:
Directory | Description |
---|---|
docs | Reference documents |
src | Source code |
--slamware_ros_sdk | Source code of Slamware ROS SDK |
--slamware_sdk | Headers 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
Node | Comments |
---|---|
slamware_ros_sdk_server_node Node | Publish 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 | ||
Field | Data type | Comments |
area | slamware_ros_sdk/RectFlt32 | Search area |
options | slamware_ros_sdk/LocalizationOptions | Relocalization options |
slamware_ros_sdk/RectFlt32 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/RectFlt32.msg | ||
Definition | ||
Field | Data type | Comments |
x | float32 | x of origin |
y | float32 | y of origin |
w | float32 | width |
h | float32 | height |
slamware_ros_sdk/LocalizationOptions | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/LocalizationOptions.msg | ||
Definition | ||
Field | Data type | 描述 |
max_time_ms | slamware_ros_sdk/OptionalInt32 | Timeout of relocalization (in ms) |
mvmt_type | slamware_ros_sdk/OptionalLocalizationMovement | Behaviour of relocalization |
slamware_ros_sdk/OptionalInt32 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/OptionalInt32.msg | ||
Definition | ||
Field | Data type | Comments |
is_valid | bool | is the value valid |
value | int32 | value |
slamware_ros_sdk/OptionalLocalizationMovement | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/OptionalLocalizationMovement.msg | ||
Definition | ||
Field | Data type | Comments |
is_valid | bool | is the value valid |
value | slamware_ros_sdk/LocalizationMovement | Relocalization behaviour |
slamware_ros_sdk/LocalizationMovement | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/LocalizationMovement.msg | ||
Definition | ||
Field | Data type | Comments |
type | int8 | Unknown=-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 | ||
Field | Data type | Comments |
kind | slamware_ros_sdk/MapKind | Map kind |
slamware_ros_sdk/MapKind | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/MapKind.msg | ||
Definition | ||
Field | Data type | Comments |
kind | int8 | Unknown=-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 | ||
Field | Data type | Comments |
enabled | bool | Enable of disable map update |
kind | slamware_ros_sdk/MapKind | Map kind |
slamware_ros_sdk/MapKind | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/MapKind.msg | ||
Definition | ||
Field | Data type | Comments |
kind | int8 | Unknown=-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 | ||
Field | Data type | Comments |
enabled | bool | 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 | ||
Field | Data type | Comments |
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 | ||
Field | Data type | Comments |
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 | ||
Field | Data type | Comments |
opt_flags | slamware_ros_sdk/MoveOptionFlag | Move options |
speed_ratio | slamware_ros_sdk/OptionalFlt64 | Max speed limit ratio |
slamware_ros_sdk/MoveOptionFlag | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/MoveOptionFlag.msg | ||
Definition | ||
Field | Data type | Comments |
flags | uint32 | Flag options |
Enumeration | ||
Enumeration | Value | Comments |
NONE | 0x00000000 | No option |
APPENDING | 0x00000001 | Append the goal to current goal queue, or replace the whole goal queue |
MILESTONE | 0x00000002 | Deprecated |
NO_SMOOTH | 0x00000004 | Do not smooth the path |
KEY_POINTS | 0x00000008 | Move via virtual tracks |
PRECISE | 0x00000010 | Move to goal precisely |
WITH_YAW | 0x00000020 | Turn to specific heading when reached target location |
RETURN_UNREACHABLE_DIRECTLY | 0x00000040 | If the goal is occupied, return unreachable directly, or find a nearby place as alternative goal |
KEY_POINTS_WITH_OA | 0x00000080 | Move with virtual-track-priority mode |
slamware_ros_sdk/OptionalFlt64 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/OptionalFlt64.msg | ||
Definition | ||
Field | Data type | Comments |
is_valid | bool | is the value valid |
value | float64 | value |
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 | ||
Field | Data type | Comments |
theta | float32 | Direction of track ball |
options | slamware_ros_sdk/MoveOptions | Movement options |
slamware_ros_sdk/MoveOptions | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/MoveOptions.msg | ||
Definition | ||
Field | Data type | Comments |
opt_flags | slamware_ros_sdk/MoveOptionFlag | Move options |
speed_ratio | slamware_ros_sdk/OptionalFlt64 | Max speed limit ratio |
slamware_ros_sdk/MoveOptionFlag | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/MoveOptionFlag.msg | ||
Definition | ||
Field | Data type | Comments |
flags | uint32 | Flag options |
Enumeration | ||
Enumeration | Value | Comments |
NONE | 0x00000000 | No option |
APPENDING | 0x00000001 | Append the goal to current goal queue, or replace the whole goal queue |
MILESTONE | 0x00000002 | Deprecated |
NO_SMOOTH | 0x00000004 | Do not smooth the path |
KEY_POINTS | 0x00000008 | Move via virtual tracks |
PRECISE | 0x00000010 | Move to goal precisely |
WITH_YAW | 0x00000020 | Turn to specific heading when reached target location |
RETURN_UNREACHABLE_DIRECTLY | 0x00000040 | If the goal is occupied, return unreachable directly, or find a nearby place as alternative goal |
KEY_POINTS_WITH_OA | 0x00000080 | Move with virtual-track-priority mode |
slamware_ros_sdk/OptionalFlt64 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/OptionalFlt64.msg | ||
Definition | ||
Field | Data type | Comments |
is_valid | bool | is the value valid |
value | float64 | value |
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 | ||
Field | Data type | Comments |
location | geometry_msgs/Point | The goal location |
options | slamware_ros_sdk/MoveOptions | Move options |
yaw | float32 | Ending robot heading |
slamware_ros_sdk/MoveOptions | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/MoveOptions.msg | ||
Definition | ||
Field | Data type | Comments |
opt_flags | slamware_ros_sdk/MoveOptionFlag | Move options |
speed_ratio | slamware_ros_sdk/OptionalFlt64 | Max speed limit ratio |
slamware_ros_sdk/MoveOptionFlag | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/MoveOptionFlag.msg | ||
Definition | ||
Field | Data type | Comments |
flags | uint32 | Flag options |
Enumeration | ||
Enumeration | Value | Comments |
NONE | 0x00000000 | No option |
APPENDING | 0x00000001 | Append the goal to current goal queue, or replace the whole goal queue |
MILESTONE | 0x00000002 | Deprecated |
NO_SMOOTH | 0x00000004 | Do not smooth the path |
KEY_POINTS | 0x00000008 | Move via virtual tracks |
PRECISE | 0x00000010 | Move to goal precisely |
WITH_YAW | 0x00000020 | Turn to specific heading when reached target location |
RETURN_UNREACHABLE_DIRECTLY | 0x00000040 | If the goal is occupied, return unreachable directly, or find a nearby place as alternative goal |
KEY_POINTS_WITH_OA | 0x00000080 | Move with virtual-track-priority mode |
slamware_ros_sdk/OptionalFlt64 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/OptionalFlt64.msg | ||
Definition | ||
Field | Data type | Comments |
is_valid | bool | is the value valid |
value | float64 | value |
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 | ||
Field | Data type | Comments |
locations | geometry_msgs/Point[] | The goal location |
options | slamware_ros_sdk/MoveOptions | Move options |
yaw | float32 | Ending robot heading |
slamware_ros_sdk/MoveOptions | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/MoveOptions.msg | ||
Definition | ||
Field | Data type | Comments |
opt_flags | slamware_ros_sdk/MoveOptionFlag | Move options |
speed_ratio | slamware_ros_sdk/OptionalFlt64 | Max speed limit ratio |
slamware_ros_sdk/MoveOptionFlag | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/MoveOptionFlag.msg | ||
Definition | ||
Field | Data type | Comments |
flags | uint32 | Flag options |
Enumeration | ||
Enumeration | Value | Comments |
NONE | 0x00000000 | No option |
APPENDING | 0x00000001 | Append the goal to current goal queue, or replace the whole goal queue |
MILESTONE | 0x00000002 | Deprecated |
NO_SMOOTH | 0x00000004 | Do not smooth the path |
KEY_POINTS | 0x00000008 | Move via virtual tracks |
PRECISE | 0x00000010 | Move to goal precisely |
WITH_YAW | 0x00000020 | Turn to specific heading when reached target location |
RETURN_UNREACHABLE_DIRECTLY | 0x00000040 | If the goal is occupied, return unreachable directly, or find a nearby place as alternative goal |
KEY_POINTS_WITH_OA | 0x00000080 | Move with virtual-track-priority mode |
slamware_ros_sdk/OptionalFlt64 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/OptionalFlt64.msg | ||
Definition | ||
Field | Data type | Comments |
is_valid | bool | is the value valid |
value | float64 | value |
rotate_to (slamware_ros_sdk/RotateToRequest)
Request rotation to specific heading
slamware_ros_sdk/RotateToRequest | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/RotateToRequest.msg | ||
Definition | ||
Field | Data type | Comments |
orientation | geometry_msgs/Quaternion | Specifying the orientation |
options | slamware_ros_sdk/MoveOptions | Move options |
slamware_ros_sdk/MoveOptions | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/MoveOptions.msg | ||
Definition | ||
Field | Data type | Comments |
opt_flags | slamware_ros_sdk/MoveOptionFlag | Move options |
speed_ratio | slamware_ros_sdk/OptionalFlt64 | Max speed limit ratio |
slamware_ros_sdk/MoveOptionFlag | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/MoveOptionFlag.msg | ||
Definition | ||
Field | Data type | Comments |
flags | uint32 | Flag options |
Enumeration | ||
Enumeration | Value | Comments |
NONE | 0x00000000 | No option |
APPENDING | 0x00000001 | Append the goal to current goal queue, or replace the whole goal queue |
MILESTONE | 0x00000002 | Deprecated |
NO_SMOOTH | 0x00000004 | Do not smooth the path |
KEY_POINTS | 0x00000008 | Move via virtual tracks |
PRECISE | 0x00000010 | Move to goal precisely |
WITH_YAW | 0x00000020 | Turn to specific heading when reached target location |
RETURN_UNREACHABLE_DIRECTLY | 0x00000040 | If the goal is occupied, return unreachable directly, or find a nearby place as alternative goal |
KEY_POINTS_WITH_OA | 0x00000080 | Move with virtual-track-priority mode |
slamware_ros_sdk/OptionalFlt64 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/OptionalFlt64.msg | ||
Definition | ||
Field | Data type | Comments |
is_valid | bool | is the value valid |
value | float64 | value |
rotate (slamware_ros_sdk/RotateRequest)
Request rotation by specific angle
slamware_ros_sdk/RotateRequest | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/RotateRequest.msg | ||
Definition | ||
Field | Data type | Comments |
orientation | geometry_msgs/Quaternion | Specifying the rotation |
options | slamware_ros_sdk/MoveOptions | Move options |
slamware_ros_sdk/MoveOptions | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/MoveOptions.msg | ||
Definition | ||
Field | Data type | Comments |
opt_flags | slamware_ros_sdk/MoveOptionFlag | Move options |
speed_ratio | slamware_ros_sdk/OptionalFlt64 | Max speed limit ratio |
slamware_ros_sdk/MoveOptionFlag | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/MoveOptionFlag.msg | ||
Definition | ||
Field | Data type | Comments |
flags | uint32 | Flag options |
Enumeration | ||
Enumeration | Value | Comments |
NONE | 0x00000000 | No option |
APPENDING | 0x00000001 | Append the goal to current goal queue, or replace the whole goal queue |
MILESTONE | 0x00000002 | Deprecated |
NO_SMOOTH | 0x00000004 | Do not smooth the path |
KEY_POINTS | 0x00000008 | Move via virtual tracks |
PRECISE | 0x00000010 | Move to goal precisely |
WITH_YAW | 0x00000020 | Turn to specific heading when reached target location |
RETURN_UNREACHABLE_DIRECTLY | 0x00000040 | If the goal is occupied, return unreachable directly, or find a nearby place as alternative goal |
KEY_POINTS_WITH_OA | 0x00000080 | Move with virtual-track-priority mode |
slamware_ros_sdk/OptionalFlt64 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/OptionalFlt64.msg | ||
Definition | ||
Field | Data type | Comments |
is_valid | bool | is the value valid |
value | float64 | value |
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 | ||
Field | Data type | Comments |
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 | ||
Field | Data type | Comments |
usage | int8 | Unknown=-1, Virtual Walls=0, Virtual Tracks=1 |
slamware_ros_sdk/Line2DFlt32 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/Line2DFlt32.msg | ||
Definition | ||
Field | Data type | Comments |
id | uint32 | Line segment id |
start | slamware_ros_sdk/Vec2DFlt32 | Start point of line segment |
end | slamware_ros_sdk/Vec2DFlt32 | End point of line segment |
slamware_ros_sdk/Vec2DFlt32 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/Vec2DFlt32.msg | ||
Definition | ||
Field | Data type | Comments |
x | float32 | x |
y | float32 | y |
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 | ||
Field | Data type | Comments |
usage | slamware_ros_sdk/ArtifactUsage | Line type |
line | slamware_ros_sdk/Line2DFlt32[] | Positions of lines |
slamware_ros_sdk/ArtifactUsage | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/ArtifactUsage.msg | ||
Definition | ||
Field | Data type | Comments |
usage | int8 | Unknown=-1, Virtual Walls=0, Virtual Tracks=1 |
slamware_ros_sdk/Line2DFlt32 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/Line2DFlt32.msg | ||
Definition | ||
Field | Data type | Comments |
id | uint32 | Line segment id |
start | slamware_ros_sdk/Vec2DFlt32 | Start point of line segment |
end | slamware_ros_sdk/Vec2DFlt32 | End point of line segment |
slamware_ros_sdk/Vec2DFlt32 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/Vec2DFlt32.msg | ||
Definition | ||
Field | Data type | Comments |
x | float32 | x |
y | float32 | y |
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 | ||
Field | Data type | Comments |
usage | slamware_ros_sdk/ArtifactUsage | Line type |
id | uint32 | Line segment id |
slamware_ros_sdk/ArtifactUsage | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/ArtifactUsage.msg | ||
Definition | ||
Field | Data type | Comments |
usage | int8 | Unknown=-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 | ||
Field | Data type | Comments |
usage | slamware_ros_sdk/ArtifactUsage | Line segment type |
slamware_ros_sdk/ArtifactUsage | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/ArtifactUsage.msg | ||
Definition | ||
Field | Data type | Comments |
usage | int8 | Unknown=-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 | ||
Field | Data type | Comments |
usage | slamware_ros_sdk/ArtifactUsage | Line segment type |
line | slamware_ros_sdk/Line2DFlt32 | New position of line segments |
slamware_ros_sdk/ArtifactUsage | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/ArtifactUsage.msg | ||
Definition | ||
Field | Data type | Comments |
usage | int8 | Unknown=-1, Virtual Walls=0, Virtual Tracks=1 |
slamware_ros_sdk/Line2DFlt32 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/Line2DFlt32.msg | ||
Definition | ||
Field | Data type | Comments |
id | uint32 | Line segment id |
start | slamware_ros_sdk/Vec2DFlt32 | Start point of line segment |
end | slamware_ros_sdk/Vec2DFlt32 | End point of line segment |
slamware_ros_sdk/Vec2DFlt32 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/Vec2DFlt32.msg | ||
Definition | ||
Field | Data type | Comments |
x | float32 | x |
y | float32 | y |
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 | ||
Field | Data type | Comments |
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 | ||
Field | Data type | Comments |
usage | int8 | Unknown=-1, Virtual Walls=0, Virtual Tracks=1 |
slamware_ros_sdk/Line2DFlt32 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/Line2DFlt32.msg | ||
Definition | ||
Field | Data type | Comments |
id | uint32 | Line segment id |
start | slamware_ros_sdk/Vec2DFlt32 | Start point of line segment |
end | slamware_ros_sdk/Vec2DFlt32 | End point of line segment |
slamware_ros_sdk/Vec2DFlt32 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/Vec2DFlt32.msg | ||
Definition | ||
Field | Data type | Comments |
x | float32 | x |
y | float32 | y |
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 | ||
Field | Data type | Comments |
sensors_info | slamware_ros_sdk/BasicSensorInfo[] | Sensor information |
slamware_ros_sdk/BasicSensorInfo | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/BasicSensorInfo.msg | ||
Definition | ||
Field | Data type | Comments |
id | int32 | Sensor ID |
sensor_type | slamware_ros_sdk/SensorType | Sensor Type |
impact_type | slamware_ros_sdk/ImpactType | Signal type (digital/analog) |
install_pose | geometry_msgs/Pose | Installation pose |
refresh_freq | float32 | Refresh rate |
slamware_ros_sdk/SensorType | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/SensorType.msg | ||
Definition | ||
Field | Data type | Comments |
type | int8 | Unknown=-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 | ||
Field | Data type | Comments |
type | int8 | Unknown=-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 | ||
Field | Data type | Comments |
values_data | slamware_ros_sdk/BasicSensorValueData[] | Sensor data |
slamware_ros_sdk/BasicSensorValueData | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/BasicSensorValueData.msg | ||
Definition | ||
Field | Data type | Comments |
info | slamware_ros_sdk/BasicSensorInfo | Sensor information |
value | slamware_ros_sdk/BasicSensorValue | Sensor value |
slamware_ros_sdk/BasicSensorValue | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/BasicSensorValue.msg | ||
Definition | ||
Field | Data type | Comments |
is_in_impact | bool | Sensor is activated or not |
value | float32 | Sensor analog value |
slamware_ros_sdk/BasicSensorInfo | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/BasicSensorInfo.msg | ||
Definition | ||
Field | Data type | Comments |
id | int32 | Sensor ID |
sensor_type | slamware_ros_sdk/SensorType | Sensor Type |
impact_type | slamware_ros_sdk/ImpactType | Signal type (digital/analog) |
install_pose | geometry_msgs/Pose | Installation pose |
refresh_freq | float32 | Refresh rate |
slamware_ros_sdk/SensorType | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/SensorType.msg | ||
Definition | ||
Field | Data type | Comments |
type | int8 | Unknown=-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 | ||
Field | Data type | Comments |
type | int8 | Unknown=-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 | ||
Field | Data type | Comments |
is_map_building_enabled | bool | Map update is enabled or not |
is_localization_enabled | bool | Localization is enabled or not |
localization_quality | int32 | Localization quality |
board_temperature | int32 | Motherboard temperature |
battery_percentage | int32 | Battery percentage |
is_dc_in | bool | Is the DC cord connected |
is_charging | bool | Is charging |
virtual_walls (slamware_ros_sdk/Line2DFlt32Array)
Virtual walls, updated periodically
slamware_ros_sdk/Line2DFlt32Array | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/Line2DFlt32Array.msg | ||
Definition | ||
Field | Data type | Comments |
lines | slamware_ros_sdk/Line2DFlt32[] | Multiple line segments |
slamware_ros_sdk/Line2DFlt32 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/Line2DFlt32.msg | ||
Definition | ||
Field | Data type | Comments |
id | uint32 | Line segment id |
start | slamware_ros_sdk/Vec2DFlt32 | Start point of line segment |
end | slamware_ros_sdk/Vec2DFlt32 | End point of line segment |
slamware_ros_sdk/Vec2DFlt32 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/Vec2DFlt32.msg | ||
Definition | ||
Field | Data type | Comments |
x | float32 | x |
y | float32 | y |
virtual_tracks (slamware_ros_sdk/Line2DFlt32Array)
Virtual tracks, updated periodically
slamware_ros_sdk/Line2DFlt32Array | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/Line2DFlt32Array.msg | ||
Definition | ||
Field | Data type | Comments |
lines | slamware_ros_sdk/Line2DFlt32[] | Multiple line segments |
slamware_ros_sdk/Line2DFlt32 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/Line2DFlt32.msg | ||
Definition | ||
Field | Data type | Comments |
id | uint32 | Line segment id |
start | slamware_ros_sdk/Vec2DFlt32 | Start point of line segment |
end | slamware_ros_sdk/Vec2DFlt32 | End point of line segment |
slamware_ros_sdk/Vec2DFlt32 | ||
---|---|---|
File | ||
slamware_ros_sdk/msg/Vec2DFlt32.msg | ||
Definition | ||
Field | Data type | Comments |
x | float32 | x |
y | float32 | y |
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 | ||
Field | Data type | Comments |
raw_stcm | int8[] | 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 | ||
Field | Data type | Comments |
raw_stcm | int8[] | uploaded stcm map data |
robot_pose | geometry_msgs/Pose | uploaded robot pose |
Response | ||
None |
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 mapbase_link -> odom
Pose estimation of the robotodom -> map
Odometry information of the robot (maybe fixed or not provided according to the configuration)