45.在ROS中实现global planner(1)

news2024/11/17 22:39:38

前文move_base介绍(4)简单介绍move_base的全局路径规划配置,接下来我们自己实现一个全局的路径规划

1. move_base规划配置

ROS1move_base可以配置选取不同的global plannerlocal planner, 默认move_base.cpp#L70中可以看到是读取该参数决定的`

    private_nh.param("base_global_planner", global_planner, std::string("navfn/NavfnROS"));
    private_nh.param("base_local_planner", local_planner, std::string("base_local_planner/TrajectoryPlannerROS"));

我们可以通过配置base_global_plannerbase_local_planner参数修改不同的算法

ros1 navigation中提供了3种base_global_planner, 分别是

  • navfn/NavfnROS
  • global_planner::GlobalPlanner
  • carrot_planner/CarrotPlanner

下面我们自己实现一个全局的路径规划,并在模拟器测试其执行效果

2. 实现原理

2.1 加载对象

private_nh.param("base_global_planner", global_planner, std::string("navfn/NavfnROS"));

上面我们已经知道 通过参数配置来决定加载哪一个全局规划器,继续跟踪可以看到

查看源码 move_base.cpp#L125 & move_base.h#L210

pluginlib::ClassLoader<nav_core::BaseGlobalPlanner> bgp_loader_;
planner_ = bgp_loader_.createInstance(global_planner);

pluginlib可以参见这里

  • pluginlib::ClassLoader<nav_core::BaseGlobalPlanner>::createInstance根据输入参数名,加载so,并且获取到库的导出类,且创建该类的一个实例
  • planner_即为该指向该实例的指针, 有了这个对象,就可以通过该成员干活了

2.2 BaseGlobalPlanner接口

planner_定义在move_base.h#L185

boost::shared_ptr<nav_core::BaseGlobalPlanner> planner_;

前面返回的planner_类型可以看到是nav_core::BaseGlobalPlanner类型,我们先来看下该类,在nav_core#L48

class BaseGlobalPlanner{
    public:
      virtual bool makePlan(const geometry_msgs::PoseStamped& start, 
          const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan) = 0;

      virtual bool makePlan(const geometry_msgs::PoseStamped& start, 
                            const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan,
                            double& cost)
      {
        cost = 0;
        return makePlan(start, goal, plan);
      }

      virtual void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros) = 0;

      virtual ~BaseGlobalPlanner(){}

    protected:
      BaseGlobalPlanner(){}
  };

可以看到该类是一个接口类,需要继承该接口做相应的实现,主要接口比较简单,就两个, initializemakePlan, 顾名思义一个初始化,一个规划路径

  • initialize
    传入了name, 以及地图信息
  • makePlan
    传入起点,目标点,返回plan

我们也可以看看在move_base对应接口的调用

  • move_base.cpp#L126
    在创建完成立即调用完成初始化

  • move_base.cpp#L496
    进行全局路径规划


  if(!planner_->makePlan(start, goal, plan) || plan.empty()){
    ...
  }

``
在MoveBase::makeplan调用了该函数,返回的plan, 保存后用于local planner的输入

3. 实现global planner

3.1 实现步骤

实现一个自己的全局规划需要下面几个步骤

  • 继承nav_core::BaseGlobalPlanner实现接口
  • 导出该实现类
  • 添加plugin.xml插件描述文件并导出
  • 修改move_base配置使用

3.2 实现接口

  • 创建包
mkdir -p ~/pibot_ros/ros_ws/src
cd ~/pibot_ros/ros_ws/src
catkin_create_pkg sample_global_planner

创建完成添加一个cpp和h文件,新增一个类继承与nav_core::BaseGlobalPlanner
上面已经看到该接口定义 我们继承并对两个接口initializemakePlan实现即可

  • initialize
    初始化我们暂时先空实现
void GlobalPlanner::initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
{
}
  • makePlan
    规划路径的接口给我们输入起点和终点,我们输出规划出的plan(如可以规划,同时返回true,反之返回false), 我们暂时不考虑具体实现,输出一条从起点到终点的直线路径,这应该是初中几何知识,比较简单如下
bool GlobalPlanner::makePlan(const geometry_msgs::PoseStamped &start,
                                const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan)
{
    ROS_INFO("make plan start:[%f %f], goal:[%f %f]", start.pose.position.x, start.pose.position.y, goal.pose.position.x, goal.pose.position.y);

    plan.clear();

    float yaw = atan2(goal.pose.position.y - start.pose.position.y, goal.pose.position.x - start.pose.position.x);

    int n = 0;
    float goal_distance = sqrt(pow((start.pose.position.x - goal.pose.position.x), 2) + pow((start.pose.position.y - goal.pose.position.y), 2));

    float delta = 0.1; // 间隔delta输出start至end的直线上的点 我们间隔0.1取直线上的所有点,放到输出的参数plan里
    while (n * delta < goal_distance)
    {
        geometry_msgs::PoseStamped pose = goal;

        pose.pose.position.x = (n * delta) * cos(yaw) + start.pose.position.x;
        pose.pose.position.y = (n * delta) * sin(yaw) + start.pose.position.y;
        ++n;
        plan.push_back(pose);
    }

    plan.push_back(goal); // 这里别忘了终点

    return !plan.empty();
}
  • 添加相应的CMakeList.txt
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
  include
  ${catkin_INCLUDE_DIRS}
)

## Declare a C++ library
add_library(${PROJECT_NAME}
  src/planner_node.cpp
)

## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})

3.3 导出类

参考navigation里面, 添加宏导出该类

PLUGINLIB_EXPORT_CLASS(sample_global_planner::GlobalPlanner, nav_core::BaseGlobalPlanner)

3.3 添加plugin.xml

添加一个bgp_plugin.xml

<library path="lib/libsample_global_planner">
  <class name="sample_global_planner/GlobalPlanner" type="sample_global_planner::GlobalPlanner" base_class_type="nav_core::BaseGlobalPlanner">
    <description>
      A sample implementation of a grid based planner 
    </description>
  </class>
</library>

3.4 编译

cd ~/pibot_ros/ros_ws
catkin_make

3.5 修改配置测试

修改~/pibot_ros/src/pibot_simulator/move_base_params.yaml

# base_global_planner: global_planner/GlobalPlanner
base_global_planner: sample_global_planner/GlobalPlanner

global_planner/GlobalPlanner ----> sample_global_planner/GlobalPlanner

  • 启动模拟器
pibot_simulator
  • 查看当前的global_planner
❯ rosparam get /move_base/base_global_planner
sample_global_planner/GlobalPlanner  # 输出sample_global_planner/GlobalPlanner表示插件已经被正确加载
  • 启动rviz发送点位,选点导航测试
pibot_view

3.6 路径显示

上面测试可以看到可以规划已经完成, dwa的局部规划已经启动, 为了方便查看全局全规划路径的输出,我们在makeplan完成后发出pathtopic

void GlobalPlanner::publishPlan(const std::vector<geometry_msgs::PoseStamped> &path)
{
    nav_msgs::Path gui_path;
    gui_path.poses.resize(path.size());

    gui_path.header.frame_id = frame_id_;
    gui_path.header.stamp = ros::Time::now();

    for (unsigned int i = 0; i < path.size(); i++)
    {
        gui_path.poses[i] = path[i];
    }

    plan_pub_.publish(gui_path);
}

把 rviz Global MapLocal Map中的dwa planner关闭, 只显示Full Plan

修改move_base_params.yamlplanner_frequency值, 0 只规划一次, >0 规划频率

3.7 测试结果

  • 选择空旷区域,可以看到可以正常规划,同时控制也可以启动完成,到达目的地
    plan2
  • 跨过障碍物,可以看到规划出路径,显然无法控制过去
    plan1

4. 总结

本文简单实现了一个global planner的插件,显然实际没啥用,不过可以作为一个模板,基于该模板实现自己的算法。后面我们将基于该模板实现可用的全局规划。

本文代码见sample_global_planner

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

如若内容造成侵权/违法违规/事实不符,请联系多彩编程网进行投诉反馈,一经查实,立即删除!

相关文章

Vue3电商项目实战-分类模块1【01-顶级类目-面包屑组件-初级、02-顶级类目-面包屑组件-高级】

文章目录01-顶级类目-面包屑组件-初级02-顶级类目-面包屑组件-高级01-顶级类目-面包屑组件-初级 目的&#xff1a; 封装一个简易的面包屑组件&#xff0c;适用于两级场景。 大致步骤&#xff1a; 准备静态的 xtx-bread.vue 组件定义 props 暴露 parentPath parentName 属性&am…

[oeasy]python0081_ANSI序列由来_终端机_VT100_DEC_VT选项_终端控制序列

更多颜色 回忆上次内容 上次 首先了解了RGB颜色设置可以把一些抽象的色彩名字 落实到具体的 RGB颜色 计算机所做的一切 其实就是量化、编码把生活的一切都进行数字化 标准 是ANSI制定的 这个ANSI 又是 怎么来的 呢&#xff1f;&#xff1f;&#x1f914; 由来 ANSI 听起…

【c++设计模式】——模板方法模式

模板方法模式的定义 定义一个操作中的算法对象的骨架&#xff08;稳定&#xff09;&#xff0c;而将一些步骤延迟到子类&#xff08;定义一个虚函数&#xff0c;让子类去实现&#xff09;&#xff0c;template method使得子类可以不改变&#xff08;复用&#xff09;一个算法结…

can协议介绍

目录 1 can协议介绍 1.1can协议 1.2 CAN协议特点 2.CAN FD 2.1 CAN FD协议简介 2.2 CAN FD协议特点 3.LIN 3.1 LIN总线简介 3.2 LIN总线特点 4. FlexRay 4.1 FlexRay简介 4.2 FlexRay特点 5. MOST 6.Ethernet 7 总结&#xff1a; 1 can协议介绍 1.1can协议 CAN…

Linux---Linux是什么

Linux 便成立的核心网站&#xff1a; http://www.kernel.org Linux是什么 Linux 就是一套操作系统 Linux 就是核心与系统呼叫接口那两层 软件移植&#xff1a;如果能够参考硬件的功能函数并据以修改你的操作系统程序代码&#xff0c; 那经过改版后的操作系统就能够在另一个硬…

Spring Boot 整合定时任务完成 从0 到1

Java 定时任务学习 定时任务概述 > 定时任务的应用场景非常广泛, 如果说 我们想要在某时某地去尝试的做某件事 就需要用到定时任务来通知我们 &#xff0c;大家可以看下面例子 如果需要明天 早起&#xff0c;哪我们一般会去定一个闹钟去通知我们, 而在编程中 有许许多多的…

ssm高校功能教室预约系统java idea maven

本网站所实现的是一个高校功能教室预约系统&#xff0c;该系统严格按照需求分析制作相关模块&#xff0c;并利用所学知识尽力完成&#xff0c;但是本人由于学识浅薄&#xff0c;无法真正做到让该程序可以投入市场使用&#xff0c;仅仅简单实现部分功能&#xff0c;希望日后还能…

springboot集成Redis

springboot集成Redis1 windows平台安装Redis2 引入依赖3 修改配置文件4 启动类添加注解5 指定缓存哪个方法6 配置Redis的超时时间小BUG测试对于项目中一些访问量较大的接口&#xff0c;配置上Redis缓存&#xff0c;提升系统运行速度。1 windows平台安装Redis github.com/Micro…

谈一谈API接口开发

做过开发的程序猿&#xff0c;基本都写过接口&#xff0c;写接口不算难事&#xff0c;与接口交互的对象核对好接口的地址、请求参数和响应参数即可&#xff0c;我在作为面试官去面试开发人员的时候&#xff0c;有时候会问这个问题&#xff0c;但相当多的一部分人并没有深入的考…

BERT(NAACL 2019)-NLP预训练大模型论文解读

文章目录摘要算法BERT预训练Masked LMNSPFine-tune BERT实验GLUESQuAD v1.1SQuAD v2.0SWAG消融实验预训练任务影响模型大小影响BERT基于特征的方法结论论文&#xff1a; 《BERT: Pre-training of Deep Bidirectional Transformers for Language Understanding》github&#xff…

QT+OpenGL 摄像机

QTOpenGL 摄像机 本篇完整工程见gitee:QtOpenGL 对应点的tag&#xff0c;由turbolove提供技术支持&#xff0c;您可以关注博主或者私信博主 OpenGL本身没有摄像机的定义&#xff0c;但是我们可以通过把场景中的所有物体往相反方向移动的方式来模拟出摄像机&#xff0c;产生一…

Linux内核启动(2,0.11版本)内核启动前的苦力活与内核启动

内核启动前的工作 在上一章的内容中&#xff0c;我们跳转到了setup.s的代码部分&#xff0c;这章我们先讲一讲setup做了什么吧 entry start start:! ok, the read went well so we get current cursor position and save it for ! posterity.mov ax,#INITSEG ! this is done …

Flowable进阶学习(十)定时器、ServiceTask服务任务、ScriptTask脚本任务

文章目录一、定时器1. 流程定义定时激活2. 流程实例定时挂起3. 定时任务执行过程ServiceTask 服务任务委托表达式表达式类中字段ScriptTask 脚本任务JS TASK一、定时器 相关知识链接阅读&#xff1a;事件网关——定时器启动事件 1. 流程定义定时激活 可以通过activateProces…

材质笔记 - Simluate Solid Surface

光的行为 当光和物体相遇时&#xff0c;光会有三种行为&#xff1a;被物体反射、穿过物体&#xff08;物体是透明或半透明的&#xff09;或者被吸收。 高光反射和漫反射 高光反射&#xff08;Specular Reflection&#xff09;会在表面光滑且反光的物体上看到&#xff0c;比如镜…

SMART PLC时间间隔定时器应用(高速脉冲测频/测速)

高速脉冲计数测量频率,专栏有系列文章分析讲解,这里不再赘述(原理都是利用差分代替微分)。具体链接如下: 西门子SMART PLC高速脉冲计数采集编码器速度(RC滤波)_RXXW_Dor的博客-CSDN博客这篇文章主要讲解西门子 SMART PLC高速计数采集编码器脉冲信号计算速度,根据编码器脉…

鸢尾花数据集分类(PyTorch实现)

一、数据集介绍 Data Set Information: This is perhaps the best known database to be found in the pattern recognition literature. Fisher’s paper is a classic in the field and is referenced frequently to this day. (See Duda & Hart, for example.) The data…

[Android Studio]Android 数据存储-文件存储学习笔记-结合保存QQ账户与密码存储到指定文件中的演练

&#x1f7e7;&#x1f7e8;&#x1f7e9;&#x1f7e6;&#x1f7ea; Android Debug&#x1f7e7;&#x1f7e8;&#x1f7e9;&#x1f7e6;&#x1f7ea; Topic 发布安卓学习过程中遇到问题解决过程&#xff0c;希望我的解决方案可以对小伙伴们有帮助。 &#x1f4cb;笔记目…

戴尔游匣G16电脑U盘安装系统操作教程分享

戴尔游匣G16电脑U盘安装系统操作教程分享。有用户在使用戴尔游匣G16电脑的时候遇到了系统问题&#xff0c;比如电脑蓝屏、自动关机重启、驱动不兼容等问题。遇到这些问题如果无法进行彻底解决&#xff0c;我们可以通过U盘重新安装系统的方法来解决&#xff0c;因为这些问题一般…

I.MX6ULL内核开发7:led字符设备驱动实验

目录 一、led字符设备驱动实验 二、驱动模块初始化 三、虚拟地址读写 四、自定义led的file_operation接口 五、拷贝数据 六、register_chrdev函数 七、 __register_chrdev函数 八、编译执行 一、led字符设备驱动实验 驱动模块内核模块(.ko)驱动接口(file_operations) …

Mysql 增删改查(一) —— 查询(条件查询where、分页limits、排序order by)

查询 select 可以认为是四个基本操作中使用最为频繁的操作&#xff0c;然而数据量比较大的时候&#xff0c;我们不可能查询所有内容&#xff0c;我们一般会搭配其他语句进行查询&#xff1a; 假如要查询某一个字段的内容&#xff0c;可以使用 where假如要查询前几条记录&#…