本页面提供的基于ROS平台开发的SLAMWARE SDK的参考。
本页内容
Get Started
下载和安装SDK
请在思岚科技官方网站上的下载与支持页面下载适合您的平台的ROS SDK并解压至本地。
目录结构
Slamware ROS SDK包含了您开发过程中可能会用到的资源、代码,其目录结构组织如下:
目录 | 说明 |
---|---|
docs | 参考文档 |
src | 源码 |
--slamware_ros_sdk | ROS SDK源码包 |
--slamware_sdk | SDK相关头文件与库文件 |
开发环境需求
基于Ubuntu 16.04操作系统,并装有ROS软件包。
硬件需求
为使用ROS SDK,您需要一台基于Slamware的移动机器人,开启并配置合适的IP地址。slamware_ros_sdk_server_node节点启动后将尝试连接该机器人。
Hello World
1.创建工作空间
将存放源码的src放入一个空的工作目录,如:catkin_ws,使用catkin工具初始化工作空间
cd catkin_ws/srccatkin_init_workspace
2.编译
cd ..catkin_make
3.配置工作空间系统环境
source devel/setup.bash
4.启动节点
若移动机器人处于AP模式,连接机器人WIFI,启动节点
roslaunch slamware_ros_sdk slamware_ros_sdk_server_node.launch ip_address:=192.168.11.1
通过rviz查看
roslaunch slamware_ros_sdk view_slamware_ros_sdk_server_node.launch
节点
节点 | 说明 |
---|---|
slamware_ros_sdk_server_node节点 | 发布地图、机器人位姿与状态信息,接收控制指令 |
slamware_ros_sdk_server_node节点
slamware_ros_sdk_server_node节点连接基于Slamware的移动机器人,发布该机器人的地图、位姿与状态信息,并接收指令用于控制设备。
1. 订阅主题
/cmd_vel (geometry_msgs/Twist)
控制机器人线速度和角速度
/move_base_simple/goal (geometry_msgs/PoseStamped)
控制机器人导航至指定地点(带Yaw角,精确到点模式)
sync_map (slamware_ros_sdk/SyncMapRequest)
地图同步
set_pose (geometry_msgs/Pose)
设置机器人指定位姿
recover_localization (slamware_ros_sdk/RecoverLocalizationRequest)
控制机器人进行重定位
clear_map (slamware_ros_sdk/ClearMapRequest)
清除地图
set_map_update (slamware_ros_sdk/SetMapUpdateRequest)
设置建图开关状态
set_map_localization (slamware_ros_sdk/SetMapLocalizationRequest)
设置定位开关状态
move_by_direction (slamware_ros_sdk/MoveByDirectionRequest)
控制机器人向指定方向移动
move_by_theta (slamware_ros_sdk/MoveByThetaRequest)
轨迹球模式控制机器人移动
move_to (slamware_ros_sdk/MoveToRequest)
控制机器人导航至指定地点,并旋转指定角度
move_to_locations (slamware_ros_sdk/MoveToLocationsRequest)
控制机器人沿着指定路径移动
rotate_to (slamware_ros_sdk/RotateToRequest)
控制机器人转动至指定的朝向
rotate (slamware_ros_sdk/RotateRequest)
控制机器人旋转指定角度
go_home (slamware_ros_sdk/GoHomeRequest)
控制机器人回桩
cancel_action (slamware_ros_sdk/CancelActionRequest)
取消所有动作
add_line (slamware_ros_sdk/AddLineRequest)
添加线段
add_lines (slamware_ros_sdk/AddLinesRequest)
添加多条线段
remove_line (slamware_ros_sdk/RemoveLineRequest)
移除指定线段
clear_lines (slamware_ros_sdk/ClearLinesRequest)
清空所有线段
move_line (slamware_ros_sdk/MoveLineRequest)
移动线段到指定位置
move_lines (slamware_ros_sdk/MoveLinesRequest)
移动多条线段到指定位置
2. 发布主题
scan (sensor_msgs/LaserScan)
激光雷达数据,定频发布
odom (nav_msgs/Odometry)
机器人位姿信息,定频发布
map_metadata (nav_msgs/MapMetaData)
地图基本信息(包括分辨率、尺寸、原点位置),定频发布
map (nav_msgs/OccupancyGrid)
地图数据,定频发布
basic_sensors_info (slamware_ros_sdk/BasicSensorInfoArray)
传感器信息(包括id、类型、数字/模拟、安装位置、刷新频率等信息),变化时发布
basic_sensors_values (slamware_ros_sdk/BasicSensorValueDataArray)
传感器数据,定频发布
global_plan_path (nav_msgs/Path)
规划路径,定频发布
robot_basic_state (slamware_ros_sdk/RobotBasicState)
机器人基本信息(包括建图开关、定位开关、主板温度、充电状态、电量等信息),定频发布
virtual_walls (slamware_ros_sdk/Line2DFlt32Array)
虚拟墙清单,定频发布
virtual_tracks (slamware_ros_sdk/Line2DFlt32Array)
虚拟轨道清单,定频发布
3. 服务
sync_get_stcm (slamware_ros_sdk/SyncGetStcm)
获取stcm地图
sync_set_stcm (slamware_ros_sdk/SyncSetStcm)
上传stcm地图
4. 参数
参数 | 类型 | 默认 | 描述 |
---|---|---|---|
ip_address | string | "192.168.11.1" | 连接机器人的IP地址 |
robot_port | int | 1445 | 连接机器人的端口 |
reconn_wait_ms | uint | 3000 | 重连等待时间,单位:毫秒 |
angle_compensate | bool | true | 角度补偿开关 |
fixed_odom_map_tf | bool | true | 固定机器人里程计信息 |
robot_frame | string | "/base_link" | 机器人基参考系 |
laser_frame | string | "/laser" | 激光参考系 |
odom_frame | string | "/odom" | 里程信息参考系 |
map_frame | string | "/map" | 地图参考系 |
robot_pose_pub_period | float | 0.05 | 机器人位姿发布周期,单位:秒 |
scan_pub_period | float | 0.1 | 激光数据发布周期,单位:秒 |
map_update_period | float | 0.2 | 地图更新周期,单位:秒 |
map_pub_period | float | 0.2 | 地图数据发布周期,单位:秒 |
basic_sensors_info_update_period | float | 7.0 | 传感器信息更新周期,单位:秒 |
basic_sensors_values_pub_period | float | 0.05 | 传感器数据发布周期,单位:秒 |
path_pub_period | float | 0.05 | 路径规划发布周期,单位:秒 |
robot_basic_state_pub_period | float | 1.0 | 机器人状态信息发布周期,单位:秒 |
virtual_walls_pub_period | float | 0.5 | 虚拟墙数据发布周期,单位:秒 |
virtual_tracks_pub_period | float | 0.5 | 虚拟轨道数据发布周期,单位:秒 |
map_sync_once_get_max_wh | float | 100.0 | 地图同步最大尺寸 |
map_update_near_robot_half_wh | float | 8.0 | 地图更新以机器人为中心的长宽尺寸 |
scan_topic | string | "scan" | 激光数据发布主题 |
odom_topic | string | "odom" | 机器人位姿发布主题 |
map_topic | string | "map" | 地图发布主题 |
map_info_topic | string | "map_metadata" | 地图信息发布主题 |
basic_sensors_info_topic | string | "basic_sensors_info" | 传感器信息发布主题 |
basic_sensors_values_topic | string | "basic_sensors_values" | 传感器数据发布主题 |
path_topic | string | "global_plan_path" | 路径规划发布主题 |
vel_control_topic | string | "/cmd_vel" | 控制机器人进行方向移动的订阅主题 |
goal_topic | string | "/move_base_simple/goal" | 控制机器人导航到指定地点的订阅主题 |
5. 监听tf变换
无
6. 广播tf变换
laser -> map
激光雷达在地图中的位姿
base_link -> odom
当前机器人在地图中的位姿估计
odom -> map
机器人里程计信息(根据配置固定或不广播)
slamware_ros_sdk/SyncMapRequest
文件
slamware_ros_sdk/msg/SyncMapRequest.msg
定义
空