move_base分析(一)使用GetPlan获得路径规划

ROS导航模块的框架如下:

要获得路径规划需要用到move_base中的一个服务make_plan,它就是用于获得从当前位姿到目标位姿的路径,其服务类型为nav_msgs/GetPlan

nav_msgs/GetPlan.srv成员如下:

1
2
3
4
5
6
7
geometry_msgs/PoseStamped start	  // 起始位姿
geometry_msgs/PoseStamped goal // 终点位姿

# 如果目标被阻挡了,规划失败时,规划器能到达的位置在x和y方向约束多少米
float32 tolerance
---
nav_msgs/Path plan // 服务端返回的路径

其中nav_msgs/Path是一个位姿数组,代表了机器人跟随的路径,定义:

1
2
Header header
geometry_msgs/PoseStamped[] poses

其实思路很简单,写一个service的客户端程序,通信move_base的get_plan,service的请求部分就是起始点的位姿, header.frame_id永远是map,返回值是路径,也是位姿数组。

代码如下:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
//路线规划代码
#include <ros/ros.h>
#include <nav_msgs/GetPlan.h>
#include <geometry_msgs/PoseStamped.h>
#include <string>
#include <boost/foreach.hpp>
#define forEach BOOST_FOREACH // c++没有foreach

void fillPathRequest(nav_msgs::GetPlan::Request &request)
{
request.start.header.frame_id ="map";
request.start.pose.position.x = 12.378;//初始位置x坐标
request.start.pose.position.y = 28.638;//初始位置y坐标
request.start.pose.orientation.w = 1.0;//方向
request.goal.header.frame_id = "map";
request.goal.pose.position.x = 18.792;//终点坐标
request.goal.pose.position.y = 29.544;
request.goal.pose.orientation.w = 1.0;
request.tolerance = 0.5; //如果不能到达目标,最近可到的约束
}
//路线规划结果回调
void callPlanningService(ros::ServiceClient &serviceClient, nav_msgs::GetPlan &srv)
{
//执行实际路径规划器
if (serviceClient.call(srv))
{
//srv.response.plan.poses 为保存结果的容器,遍历取出
if (!srv.response.plan.poses.empty()) // empty()判断
{
forEach(const geometry_msgs::PoseStamped &p, srv.response.plan.poses)
{
// 一系列点的位姿
ROS_INFO("x = %f, y = %f", p.pose.position.x, p.pose.position.y);
}
}
else
{
ROS_WARN("Got empty plan");
}
}
else {
ROS_ERROR("Failed to call service %s - is the robot moving?",
serviceClient.getService().c_str());
}
}

int main(int argc, char** argv)
{
ros::init(argc, argv, "make_plan_node");
ros::NodeHandle nh;
// Init service query for make plan
//初始化路径规划服务,服务名称为"move_base_node/make_plan"
std::string service_name = "move_base_node/make_plan";
//等待服务空闲,如果已经在运行这个服务,会等到运行结束。
while (!ros::service::waitForService(service_name, ros::Duration(3.0))) {
ROS_INFO("Waiting for service move_base/make_plan to become available");
}
// 服务的客户端,类型就是 nav_msgs::GetPlan
ros::ServiceClient serviceClient = nh.serviceClient<nav_msgs::GetPlan>(service_name, true);
if (!serviceClient) {
ROS_FATAL("Could not initialize get plan service from %s",
serviceClient.getService().c_str());
return -1;
}
nav_msgs::GetPlan srv;
//请求服务:规划路线
fillPathRequest(srv.request);
if (!serviceClient) {
ROS_FATAL("Persistent service connection to %s failed",
serviceClient.getService().c_str());
return -1;
}
ROS_INFO("conntect to %s",serviceClient.getService().c_str());
callPlanningService(serviceClient, srv);
}

有时路径规划失败会报错: