ROS机器人启动move base时代价地图概率性无法加载的原因及解决方法

   最近,使用ROS机器人,在启动move_base 节点时,概率性会出现全局和局部代价地图不加载的问题,此时,发布目标点也无法启动路径规划。而且该问题有时候出现概率很低,比如启动10次,会有1次发送该情况,有时候概率又比较高,运气最差的一次,启动了8次才正常启动。

   上图中,是正常情况下,rviz显示的局部代价地图,在确保rviz已经配置了显示局部代价地图后,上述异常情况下,该局部代价地图不会显示。此时,rviz的局部代价地图的map配置中会显示No map received,通过rostopic echo在终端打印局部代价地图信息,会发现该消息没有被发布出来。

   在比赛过程中,若遇到这个问题,纯纯搞心态,初赛中,8分钟的比赛时间,卡在代价地图无法正常加载浪费了至少1分钟,所以还是下定决心要刨根问底,解决这个隐患。

   为了找到异常启动 move_base 节点时程序是否卡在了某个地方,从而导致代价地图没有加载出来,我先后在move_base、costmap_2d、global_planner功能包的初始化函数(构造函数)以及调用的相关函数编写打印了大量的流程运行信息,用来分析程序卡在了什么地方。

在这里插入图片描述

在这里插入图片描述

   经过层层套娃式深入探究和分析,最终确定上述异常的代价地图为正常加载是卡在了位于move_base构造函数中调用的以下函数中

planner_costmap_ros_->start();

   planner_costmap_ros_中的start()函数具体程序位于costmap_2d_ros.cpp中,我添加了标志信息后的程序如下所示:

void Costmap2DROS::start()
{ROS_INFO("c1");std::vector < boost::shared_ptr<Layer> > *plugins = layered_costmap_->getPlugins();ROS_INFO("c2");// check if we're stopped or just pausedif (stopped_){// if we're stopped we need to re-subscribe to topicsfor (vector<boost::shared_ptr<Layer> >::iterator plugin = plugins->begin(); plugin != plugins->end();++plugin){(*plugin)->activate();}stopped_ = false;}stop_updates_ = false;ROS_INFO("c3");// block until the costmap is re-initialized.. meaning one update cycle has runros::Rate r(100.0);ROS_INFO("initialized_: %d", initialized_);while (ros::ok() && !initialized_)r.sleep();ROS_INFO("c4");
}

   上述异常导致此处调用start函数时的initialized_值为0,从而卡在了start函数的while循环中,从而使得move_base中planner_costmap_ros_->start()语句后的初始化部分未能执行,从而导致代价地图未能加载。

   正常情况下,调用start函数时initialized_值为1。后来我深入探究了为什么有时候程序运行到planner_costmap_ros_->start()语句时,initialized_值为1(正常情况),有时候initialized_值为0(异常情况)。

   经过层层套娃式分析,最终锁定到了costmap_2d_ros.cpp中的void Costmap2DROS::updateMap()函数中的layered_costmap_->updateMap(x, y, yaw);函数中

void Costmap2DROS::updateMap()
{ROS_INFO("true 490");if (!stop_updates_){ROS_INFO("true 495");// get global posegeometry_msgs::PoseStamped pose;if (getRobotPose (pose)){double x = pose.pose.position.x,y = pose.pose.position.y,yaw = tf2::getYaw(pose.pose.orientation);ROS_INFO("up1");layered_costmap_->updateMap(x, y, yaw);ROS_INFO("up2");geometry_msgs::PolygonStamped footprint;footprint.header.frame_id = global_frame_;footprint.header.stamp = ros::Time::now();ROS_INFO("up3");transformFootprint(x, y, yaw, padded_footprint_, footprint);ROS_INFO("up4");footprint_pub_.publish(footprint);ROS_INFO("up5");initialized_ = true;ROS_INFO("true 505");}}
}

   根本原因是正常情况下和异常情况下layered_costmap的updateMap(x, y, yaw)函数执行速度不同,导致了这个将initialized_值置为1的线程与另一个通过planner_costmap_ros_->pause()将initialized_值置为0的线程在正常和异常情况下的执行顺序不同,正常情况下另一个将initialized_值置为0的线程先执行,然后将其值置为1的线程后执行,异常情况下则相反,此时导致本线程程序卡在start函数,而不能正常运行。


   至于该问题的解决方法,我编写了一个Costmap2DROS类的成员函数force_start(),在该函数中将initialized_的值强制置为1。然后在move_base.cpp文件中执行planner_costmap_ros_->start();之前,先执行该planner_costmap_ros_->force_start();语句,将initialized_的值强制置为1,此时,便不会出现上述程序卡在start()函数的情况。

planner_costmap_ros_->force_start();

   添加在costmap_2d_ros.cpp文件中的force_start()函数的具体程序如下:

void Costmap2DROS::force_start()
{initialized_ = true;ROS_INFO("initialized_ force_start");}

   添加在costmap_2d_ros.h文件中Costmap2DROS类中的force_start()函数的声明如下:

  /*** @brief  initialized_ force_start*/void force_start();

   至此,经过以上修改,在启动move_base 节点时,概率性会出现全局和局部代价地图不加载的问题,就可以得到解决。


本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.rhkb.cn/news/95257.html

如若内容造成侵权/违法违规/事实不符,请联系长河编程网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

进行 200 瓦太阳能 (PV) 模块设计以测量太阳能光伏阵列的电压、电流和功率、综合负荷频率和电压控制系统的方法研究(Simulink实现)

&#x1f4a5;&#x1f4a5;&#x1f49e;&#x1f49e;欢迎来到本博客❤️❤️&#x1f4a5;&#x1f4a5; &#x1f3c6;博主优势&#xff1a;&#x1f31e;&#x1f31e;&#x1f31e;博客内容尽量做到思维缜密&#xff0c;逻辑清晰&#xff0c;为了方便读者。 ⛳️座右铭&a…

构建可远程访问的企业内部论坛

文章目录 前言1.cpolar、PHPStudy2.Discuz3.打开PHPStudy&#xff0c;安装网页论坛所需软件4.进行网页运行环境的构建5.运行Discuz网页程序6.使用cpolar建立穿透内网的数据隧道&#xff0c;发布到公网7.对云端保留的空白数据隧道进行配置8.Discuz论坛搭建完毕 前言 企业在发展…

Beats:使用 Filebeat 将 golang 应用程序记录到 Elasticsearch - 8.x

毫无疑问&#xff0c;日志记录是任何应用程序最重要的方面之一。 当事情出错时&#xff08;而且确实会出错&#xff09;&#xff0c;我们需要知道发生了什么。 为了实现这一目标&#xff0c;我们可以设置 Filebeat 从我们的 golang 应用程序收集日志&#xff0c;然后将它们发送…

matlab RANSAC拟合多项式曲线

目录 一、功能概述1、算法概述2、主要函数3、参考文献二、代码实现三、结果展示四、参考链接本文由CSDN点云侠原创,原文链接。爬虫网站自重,把自己当个人。爬些不完整的误导别人有意思吗???? 一、功能概述 1、算法概述 使用RANSAC对点进行多项式拟合。

​《乡村振兴战略下传统村落文化旅游设计 》在2023年畅销榜排名465位

​《乡村振兴战略下传统村落文化旅游设计 》在2023年畅销榜排名465位

原型设计必备,10个简单好用的界面工具推荐

在数字产品和应用设计过程中,使用简单实用的界面原型设计工具至关重要。它可以将设计理念快速转换为交互原型,便于团队成员之间的沟通和协作。对设计新人来说,选择一个上手快速、功能强大的界面原型设计工具尤其关键。本文将推荐10款常用的界面原型设计工具,帮助初学者找到适合…

Vue2集成Echarts实现可视化图表

一、依赖配置 1、引入echarts相关依赖 也可以卸载原有的&#xff0c;重新安装 卸载&#xff1a;npm uninstall echarts --save 安装&#xff1a;npm install echarts4.8.0 --save 引入水球图形依赖 npm install echarts-liquidfill2.0.2 --save 水球图可参考文档&#xff1…

【先进PID控制算法(ADRC,TD,ESO)加入永磁同步电机发电控制仿真模型研究(Matlab代码实现)

&#x1f4a5;&#x1f4a5;&#x1f49e;&#x1f49e;欢迎来到本博客❤️❤️&#x1f4a5;&#x1f4a5; &#x1f3c6;博主优势&#xff1a;&#x1f31e;&#x1f31e;&#x1f31e;博客内容尽量做到思维缜密&#xff0c;逻辑清晰&#xff0c;为了方便读者。 ⛳️座右铭&a…

全面解析 Axios 请求库的基本使用方法

Axios 是一个流行的基于 Promise 的 HTTP 请求库&#xff0c;用于在浏览器和 Node.js 中进行 HTTP 请求。它提供了简单易用的 API&#xff0c;可以发送各种类型的请求&#xff08;如 GET、POST、PUT、DELETE等&#xff09;&#xff0c;并处理响应数据&#xff0c;Axios 在前端工…

lvs集群与nat模式

一&#xff0c;什么是集群&#xff1a; 集群&#xff0c;群集&#xff0c;Cluster&#xff0c;由多台主机构成&#xff0c;但是对外只表现为一个整体&#xff0c;只提供一个访问入口&#xff08;域名与ip地址&#xff09;&#xff0c;相当于一台大型计算机。 二&#xff0c;集…

算法通关村第4关【白银】| 栈的经典算法问题

1.括号匹配问题 思路&#xff1a;将左括号压入栈中&#xff0c;遍历字符串&#xff0c;当遇到右括号就出栈&#xff0c;判断是否是匹配的一对&#xff0c;不是就返回false&#xff08;因为按照顺序所以当遇到右括号出栈一定要是匹配的&#xff09;。使用Map来简化ifelse clas…

Compose - 修饰符 Modifier

一、概念 四大使用场景&#xff1a; 修改外观&#xff08;尺寸、样式、布局、行为&#xff09;。添加额外信息&#xff08;如无障碍标签&#xff09;。添加交互功能&#xff08;点击、滚动、拖拽、缩放&#xff09;。处理用户输入。 1.1 为组合函数添加 Modifier 参数 任何一…

kafka的位移

文章目录 概要消费位移__consumer_offsets主题位移提交 概要 本文主要总结kafka的位移是如何管理的&#xff0c;在broker端如何通过命令行查看到位移信息&#xff0c;并从代码层面总结了位移的提交方式。 消费位移 对于 Kafka 中的分区而言&#xff0c;它的每条消息都有唯一…

LVS-DR的RS进行ARP抑制的原因和LVS持久连接配置

一.RS的ARP抑制 1.为什么要抑制 2.如何抑制 &#xff08;1&#xff09;修改/etc/sysctl.conf文件&#xff0c;增加以下内容 &#xff08;2&#xff09;命令行临时设置 二.LVS持久连接 1.客户端持久连接 2.端口持久连接 3.防火墙标记持久连接 一.RS的ARP抑制 1.为什么要…

C++--红黑树

1.什么是红黑树 红黑树&#xff0c;是一种二叉搜索树&#xff0c;但在每个结点上增加一个存储位表示结点的颜色&#xff0c;可以是Red或Black。 通过对任何一条从根到叶子的路径上各个结点着色方式的限制&#xff0c;红黑树确保没有一条路径会比其他路径长出俩倍&#xff0c;因…

解决c/c++ Error: redefinition of ‘xxx’ 的问题

错误信息 两个类/文件同时引用定义ReplyInfo的头文件&#xff0c;会造成头文件中定义重复定义 如两个类/文件重复引用massage文件报错 message.h:36:16: error: redefinition of struct MSG_SERVOCTRL message.h:40:2: error: conflicting types for servoctrl解决 一般是目…

计算机组成与设计 Patterson Hennessy 笔记(一)MIPS 指令集

计算机的语言&#xff1a;汇编指令集 也就是指令集。本书主要介绍 MIPS 指令集。 汇编指令 算数运算&#xff1a; add a,b,c # abc sub a,b,c # ab-cMIPS 汇编的注释是 # 号。 由于MIPS中寄存器大小32位&#xff0c;是基本访问单位&#xff0c;因此也被称为一个字 word。M…

YOLOv5改进系列(21)——替换主干网络之RepViT(清华 ICCV 2023|最新开源移动端ViT)

【YOLOv5改进系列】前期回顾: YOLOv5改进系列(0)——重要性能指标与训练结果评价及分析 YOLOv5改进系列(1)——添加SE注意力机制 YOLOv5改进系列(2

React 之 Suspense和lazy

一. Suspense 参考链接&#xff1a;https://react.docschina.org/reference/react/Suspense suspense&#xff1a;n. 焦虑、悬念 <Suspense> 允许你显示一个退路方案&#xff08;fallback&#xff09;直到它的所有子组件完成加载。 <Suspense fallback{<Loadin…

vue项目根据word模版导出word文件

一、安装依赖 //1、docxtemplaternpm install docxtemplater pizzip -S//2、jszip-utilsnpm install jszip-utils -S//3、pizzipnpm install pizzip -S//4、FileSaver npm install file-saver --save二、创建word模版 也就是编辑一个word文档&#xff0c;文档中需要动态取值的…