SLAM 导航服务接口
定位相关接口
点云数据聚合服务接口
简介
该接口用于订阅 ROS2 的 merged_points
topic,以获取多固态雷达聚合后的点云数据。
Action 名称 | Action 消息类型 | 角色 |
---|---|---|
merged_points | sensor_msgs/msg/PointCloud2 | 订阅方 |
消息结构 & 主要字段说明
sensor_msgs/msg/PointCloud2 的消息结构及字段说明见
LiDAR服务接口
文档描述。
注意事项
点云数据聚合的前提条件是LiDAR ROS2节点正常启动并发布话题数据livox/lidar
,可通过ros2 node info pointcloud_accumutor_node
查看接口节点的输入话题,并通过检查话题数据是否正常。
点云降采样服务接口
简介
该接口用于订阅 ROS2 的 downsampled_points
topic,以获取降采样后的点云数据。
Action 名称 | Action 消息类型 | 角色 |
---|---|---|
downsampled_points | sensor_msgs/msg/PointCloud2 | 订阅方 |
消息结构 & 主要字段说明
sensor_msgs/msg/PointCloud2 的消息结构及字段说明见
LiDAR服务接口
文档描述。
注意事项
点云降采样服务接口生效的前提条件是LiDAR ROS2节点正常启动并发布话题数据livox/lidar
及merged_points
topic。
重定位接口
简介
该接口用于请求 ROS2 的 set_initialpose
service 服务,以进行重定位时的机器人在map坐标系的初始位置设置。
Action 名称 | Action 消息类型 | 角色 |
---|---|---|
set_initialpose | daystar_navigation_msgs/srv/SetInitialPose | 请求方 |
消息结构
# --- request ---
geometry_msgs/PoseWithCovarianceStamped init_pose
# --- response ---
bool result
geometry_msgs/PoseWithCovarianceStamped result_pose
主要字段说明
init_pose
:重定位时设置的初始位姿,带有时间戳和协方差的位姿消息。
result
:重定位是否成功的标志位。
result_pose
:经过重定位调整验证后的实际位姿信息。
注意事项
- 重定位的初始位姿可通过将机器人移动到已知点位然后获取,或通过rviz进行获取。
- 重定位成功后,定位模块会通过
tf
topic 将各坐标系间的转换关系进行发布,并应用于导航规控过程。
导航规控接口
智能导航发起接口
简介
该接口用于订阅 ROS2 的 /intelligent_navigat_to_pose
action 请求,以进行智能导航请求及相关配置设置。
Action 名称 | Action 消息类型 | 角色 |
---|---|---|
intelligent_navigat_to_pose | daystar_navigation_msgs/action/IntelligentNavitateToPose | 请求方 |
消息结构
# --- goal ---
daystar_navigation_msgs/TravelParams travel_params # 行程参数
daystar_navigation_msgs/SpeedMode speed_mode
daystar_navigation_msgs/Gait gait
daystar_navigation_msgs/ObstacleParams obstacle_params
bool disable_body_obstacle_avoidance
bool ignore_final_yaw
daystar_navigation_msgs/NavMode nav_mode
int8 direction_constraint
geometry_msgs/PoseStamped pose
bool should_stop
# --- result ---
string message
bool result
# --- feedback ---
geometry_msgs/PoseStamped current_pose
daystar_navigation_msgs/NavState current_state
主要字段说明
travel_params
:行程参数
speed_mode
:速度模式设置,限制最高速度;低速2,默认
,中速1
,高速3
gait
:步态模式设置,对角小跑步态2
,斜坡步态5
,感知楼梯步态6
,普通楼梯步态7
height
:高度模式设置,低姿态2
,正常姿态1
,高姿态3
obstacle_params
:障碍物模式设置disable_body_obstacle_avoidance
:是否停用停障,停用true
,启用false
path_following_mode
:导航模式设置,巡线模式1,4
,自由导航模式2
,智能导航模式3
direction_constrain
:前进方向设置,正走3
,倒走4
pose
:目标位姿,包含目标位置position
和以四元数形式表示的朝向orientation
。
current_pose
:反馈信息,指示当前定位位姿。
current_state
:反馈信息,指示当前导航状态。
测试方法
- 使用以下命令向智能导航发起请求:
ros2 action send_goal /nav/intelligent_navigate_to_pose daystar_navigation_msgs/action/IntelligentNavitateToPose "
travel_params:
speed_mode:
value: 2
gait:
gait: 5
obstacle_params:
disable_body_obstacle_avoidance: true
path_following_mode: 4
direction_constraint: 3
height: 1
pose:
header:
stamp:
sec: 0
nanosec: 0
frame_id: 'map'
pose:
position:
x: <target_pose_.x>
y: <target_pose_.y>
z: <target_pose_.z>
orientation:
x: <target_ori_.x>
y: <target_ori_.y>
z: <target_ori_.z>
w: <target_ori_.w>
"
注意事项
- 确保ROS2节点已启动,action_server 正常启动。
- 发布的消息格式必须严格符合
daystar_navigation_msgs/action/IntelligentNavitateToPose
消息类型的定义。 - 请务必校验步态模式设置、前进方向设置等相关属性与测试环境相契合。
规划器发起接口
简介
该接口用于 ROS2 导航规划器的 compute_path_to_pose
action 请求,以进行导航规划器模块求解。
Action 名称 | Action 消息类型 | 角色 |
---|---|---|
compute_path_to_pose | nav2_msgs/action/ComputePathToPose | 请求方 |
消息结构
# goal
geometry_msgs/PoseStamped goal
geometry_msgs/PoseStamped start
string planner_id
bool use_start
# --- result ---
nav_msgs/Path path
builtin_interfaces/Duration planning_time
主要字段说明
goal
:机器人需要到达的目标位置和方向,为带有时间戳的位姿消息。start
:机器人开始规划的起始位置和方向,为带有时间戳的位姿消息。planner_id
:用于指定使用的路径规划器的ID。use_start
:用于指示是否使用提供的start
位姿作为规划的起点。true
为使用提供的start
位姿;false
为使用机器人当前的位置作为规划起点。path
:路径消息,表示规划器生成的路径。Path
消息包含一个header
和一个poses
数组,数组中的每个元素都是一个PoseStamped
,表示路径中的一个点。planning_time
:表示规划器生成路径所花费的时间。
控制器发起接口
简介
该接口用于 ROS2 导航控制器的 follow_path
action 请求,以进行导航控制器模块求解。
Action 名称 | Action 消息类型 | 角色 |
---|---|---|
follow_path | nav2_msgs/action/FollowPath | 请求方 |
消息结构
# --- goal ---
nav_msgs/Path path
string controller_id
string goal_checker_id
# --- result ---
std_msgs/Empty result
# --- feedback ---
float32 distance_to_goal
float32 speed
主要字段说明
path
:路径消息,表示机器人需要跟随的路径。Path
消息包含一个header
(时间戳和坐标系信息)和一个poses
数组,数组中的每个元素都是一个PoseStamped
,表示路径中的一个点。controller_id
:指定使用的控制器ID。goal_checker_id
:指定使用的目标检查器ID。distance_to_goal
:反馈信息,机器人当前距离目标位置的剩余距离。speed
:反馈信息,机器人当前的运动速度。