#ROS导航代码报错:[move_base-3] process has died [pid 7588, exit code 1, cmd /home/wheeltec-client/wheeltec_robot/devel/lib/move_base/move_base __name:=move_base __log:=/home/wheeltec-client/.ros/log/3a3df818-ebe7-11ed-afab-000c2926fa04/move_base-3.log].已解决
导航参考代码
参考这位老哥的RRT*代码:https://zhuanlan.zhihu.com/p/336867657
移植
参考了这位大哥的移植方法:https://blog.csdn.net/bluewhalerobot/article/details/73771020?utm_source=blogxgwz4
拿carrot_planner魔改再一顿复制粘贴就行。理论上来说,只要命名和内容都改完了,就没太大问题了。
报错
Failed to create the rrt_star_planner/RRTSTARPlanner planner, are you
sure it is properly registered and that the containing library is
built? Exception: MultiLibraryClassLoader: Could not create object of
class type rt_star_planner::RRTSTARPlanner as no factory exists for it.
Make sure that the library exists and was explicitly loaded through
MultiLibraryClassLoader::loadLibrary()
这是一开始发现的报错。结果发现是改代码时 rrt_star_planner::RRTSTARPlanner 写错写成了 rt_star_planner::RRTSTARPlanner。这种错误基本根据报错提示就能改正。
另外,有时也报错:
Failed to create the rrt_star_planner/RRTSTARPlanner planner, are you
sure it is properly registered and that the containing library is built?
的话,貌似可以通过运行setup.bash来使工作环境配置生效。
在工作空间文件夹运行:
source devel/setup.bash
有可能会解决问题。
重难点报错
只针对上述老大哥的代码哈~
process has died [pid 16501, exit code -11, cmd /home/wheeltec-client/wheeltec_robot/devel/lib/move_base/move_base __name:=move_base __log:=/home/wheeltec-client/.ros/log/128979f2-ec12-11ed-afab-000c2926fa04/move_base-3.log].
log file: /home/wheeltec-client/.ros/log/128979f2-ec12-11ed-afab-000c2926fa04/move_base-3*.log
这个报错是在利用Gazebo仿真导航launch文件运行后,再Rviz界面下使用Publish point设置初始点和目标点时会产生的。
由于哥们ROS不太懂,参考ROS官方导航代码planner_core.cpp中有:
bool GlobalPlanner::makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp) {
makePlan(req.start, req.goal, resp.plan.poses);
resp.plan.header.stamp = ros::Time::now();
resp.plan.header.frame_id = frame_id_;
return true;
}
这样一个非常神秘的函数,但是老大哥的代码里并没有,于是仿照这个我也写了一个:
bool RRTSTARPlanner::makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp) {
makePlan(req.start, req.goal, resp.plan.poses);
resp.plan.header.stamp = ros::Time::now();
resp.plan.header.frame_id = frame_id_;
return true;
}
在初始化函数下还加上了:
make_plan_service_ = private_nh.advertiseService("make_plan", &PlannerWithCostmap::makePlanService, this);
在头文件里加上了函数声明,结果该报错还是报错。(我甚至怀疑是move_base中的代码错了。)
解决
哥们只会笨办法,把 ROS_WARN(“ABCD”); 这个放到makeplan函数里寻找程序到底是在哪个位置崩了。终于发现,在一开始声明节点数组(叫容器吗?我不知道叫什么)时:
std::vector<Node> nodes;
貌似定义了一个空数组,里面没有东西。
接着在寻找最接近的节点时,直接引用这个:
node_nearest = getNearest(nodes, p_rand); // The nearest node of the random point
原函数:
Node RRTSTARPlanner::getNearest(std::vector<Node> nodes, std::pair<float, float> p_rand)
{
Node node = nodes[0];
for (int i = 1; i < nodes.size(); i++)
{
if (distance(nodes[i].x, nodes[i].y, p_rand.first, p_rand.second) < distance(node.x, node.y, p_rand.first, p_rand.second))
node = nodes[i];
}
return node;
}
大概是因为其中没有节点,所以就报错了。
于是,在定义了起始节点之后,我就把起始节点加进去了:
Node start_node;
start_node.x = start.pose.position.x;
start_node.y = start.pose.position.y;
start_node.node_id = 0;
start_node.parent_id = -1; // None parent node
start_node.cost = 0.0;
nodes.push_back(start_node); //只有这一句是我加的
然后问题就解决了。
总结
我估计就是具体情况具体分析,一般就是某部分代码错了。如果你也可以像我一样,用 ROS_WARN(“ABCD”); 找代码运行到什么位置崩了,那真的是。。。!