ROS2从入门到精通4-4:局部控制插件开发案例(以PID算法为例)

目录

  • 0 专栏介绍
  • 1 控制插件编写模板
    • 1.1 构造控制插件类
    • 1.2 注册并导出插件
    • 1.3 编译与使用插件
  • 2 基于PID的路径跟踪原理
  • 3 控制插件开发案例(PID算法)
  • 常见问题

0 专栏介绍

本专栏旨在通过对ROS2的系统学习,掌握ROS2底层基本分布式原理,并具有机器人建模和应用ROS2进行实际项目的开发和调试的工程能力。

🚀详情:《ROS2从入门到精通》


1 控制插件编写模板

1.1 构造控制插件类

所有全局规划插件的基类是nav2_core::Controller,该基类提供了7个纯虚方法来实现控制器插件,一个合法的控制插件必须覆盖这7个基本方法:

  • configure():在控制器服务器进入on_configure状态时会调用此方法,此方法执行ROS2参数声明和控制器成员变量的初始化;
  • activate():在控制器服务器进入on_activate状态时会调用此方法,此方法实现控制器进入活动状态前的必要操作;
  • deactivate():在控制器服务器进入on_deactivate状态时会调用此方法,此方法实现控制器进入非活动状态前的必要操作;
  • cleanup():在控制器服务器进入on_cleanup状态时会调用此方法,此方法清理为控制器创建的各种资源;
  • setPlan():当全局路径更新时调用该方法,此方法应执行转换、处理全局路径并存储的操作。
  • computeVelocityCommands():当控制器服务器需要一个新的速度命令以便机器人跟随全局路径时调用该方法。此方法返回一个geometry_msgs::msg::TwistStamped,表示机器人驱动的速度命令。此方法传递两个参数:当前机器人姿势的引用和当前速度。
  • setSpeedLimit():当需要限制机器人的最大线速度时调用该方法。速度限制可以用绝对值(m/s)或相对于最大机器人速度的百分比表示。请注意,通常,最大旋转速度会与最大线速度的变化成比例地限制,以保持当前机器人行为不受影响

此外还有一个可选的覆盖方法:

  • cancel():当控制器服务器接收到取消请求时调用该方法。如果未实现此方法,控制器将立即停止。如果实现了此方法,控制器可以执行更优雅的停止,并在完成时向控制器服务器发出信号。

按照上述标准,本文案例中PID控制器的基本成员函数和变量如下所示

namespace pid_controller
{/*** @class pid_controller::PIDController* @brief PIDController plugin*/
class PIDController : public nav2_core::Controller
{
public:/*** @brief Constructor for pid_controller::PIDController*/PIDController() = default;/*** @brief Destrructor for pid_controller::PIDController*/~PIDController() override = default;/*** @brief Configure controller state machine*/void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr& parent, std::string name,std::shared_ptr<tf2_ros::Buffer> tf,std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;/*** @brief Cleanup controller state machine*/void cleanup() override;/*** @brief Activate controller state machine*/void activate() override;/*** @brief Deactivate controller state machine*/void deactivate() override;/*** @brief Compute the best command given the current pose and velocity, with possible debug information*/geometry_msgs::msg::TwistStamped computeVelocityCommands(const geometry_msgs::msg::PoseStamped& pose,const geometry_msgs::msg::Twist& velocity,nav2_core::GoalChecker* /*goal_checker*/) override;/*** @brief Sets the global plan*/void setPlan(const nav_msgs::msg::Path& path) override;/*** @brief Limits the maximum linear speed of the robot.*/void setSpeedLimit(const double& speed_limit, const bool& percentage) override;protected:rclcpp_lifecycle::LifecycleNode::WeakPtr node_;std::shared_ptr<tf2_ros::Buffer> tf_;std::string plugin_name_;std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;nav2_costmap_2d::Costmap2D* costmap_;rclcpp::Logger logger_{ rclcpp::get_logger("PIDController") };rclcpp::Clock::SharedPtr clock_;std::mutex mutex_;
};}  // namespace pid_controller

1.2 注册并导出插件

在创建了自定义规划器的前提下,需要导出该控制器插件以便控制器服务器可以在运行时正确地加载。在ROS2中,插件的导出和加载由pluginlib处理。

  • 源文件配置导出宏

    #include "pluginlib/class_list_macros.hpp"
    PLUGINLIB_EXPORT_CLASS(pid_controller::PIDController, nav2_core::Controller)
    
  • 配置插件描述文件xxx_controller_plugin.xml,例如本案例为pid_controller_plugin.xml文件。此XML文件包含以下信息:

    • library path:插件库名称及其位置;
    • class name:控制算法类的名称;
    • class type:控制算法类的类型;
    • base class:控制基类的名称,统一为nav2_core::Controller
    • description:插件的描述。

    实例如下

    <library path="pid_controller_plugin"><class name="pid_controller/PIDController" type="pid_controller::PIDController" base_class_type="nav2_core::Controller"><description>This is an example of pid controller.</description></class>
    </library>
    
  • 配置CMakeLists.txt文件
    使用cmake函数pluginlib_export_plugin_description_file()来导出插件。这个函数会将插件描述文件安装到install/share目录中,并设置ament索引以使其可被发现,实例如下

    pluginlib_export_plugin_description_file(nav2_core pid_controller_plugin.xml)
    
  • 配置package.xml描述文件,实例如下:

    <export><build_type>ament_cmake</build_type><nav2_core plugin="${prefix}/pid_controller_plugin.xml" />
    </export>
    

1.3 编译与使用插件

编译该插件软件包,接着通过配置文件使用插件。

参数的传递链如下:首先在simulation.launch.py中引用配置文件navigation.yaml

declare_params_file_cmd = DeclareLaunchArgument('params_file',default_value=os.path.join(simulation_dir, 'config', 'navigation.yaml'),description='Full path to the ROS2 parameters file to use for all launched nodes')

接着在navigation.yaml中修改插件配置,默认如下,是用的是DWBLocalPlanner插件:

controller_server:ros__parameters:controller_plugins: ["FollowPath"]# DWB parametersFollowPath:plugin: "dwb_core::DWBLocalPlanner"min_vel_x: 0.0min_vel_y: 0.0max_vel_x: 0.26max_vel_y: 0.0max_vel_theta: 1.0min_speed_xy: 0.0max_speed_xy: 0.26min_speed_theta: 0.0...

将上述替换为自己的插件,本案例为:

controller_server:ros__parameters:controller_plugins: ["FollowPath"]FollowPath: plugin: "pid_controller/PIDController"

接着运行路径规划即可看到控制算法被替换

2 基于PID的路径跟踪原理

PID控制是一种常用的经典控制算法,其应用背景广泛,例如

  • 工业自动化控制:温度控制、压力控制、流量控制、液位控制等过程控制系统多采用PID闭环,可以帮助维持系统参数在设定值附近,以提高生产过程的稳定性和效率;
  • 机械工程:PID算法可用于实现精确的运动控制,包括控制位置、速度和力。这包括机器人控制、电机控制、汽车巡航控制等;
  • 农业自动化:PID算法可用于控制温室环境,包括温度、湿度和光照,以促进植物的生长和提高农业生产;

PID代表比例(Proportional)积分(Integral)微分(Derivative),它通过根据误差信号的大小和变化率来调整控制器的输出,以使系统的输出尽可能接近期望值,其控制框图如下所示

在这里插入图片描述

在基于PID的局部路径规划中,希望机器人能快速跟踪上预设的轨迹,设误差量为 e k e_k ek e k e_k ek可以根据实际的控制目标进行选择,例如线速度误差、角速度误差、轨迹跟踪误差等

在这里插入图片描述

以轨迹跟踪误差为例,如图所示,根据几何关系可得

e k = sin ⁡ ( θ k , d − θ k ) ⋅ d k e_k=\sin \left( \theta _{k,d}-\theta _k \right) \cdot d_k ek=sin(θk,dθk)dk

其中

θ k , d = a tan ⁡ ( y k , d − y k , x k , d − x k ) d k = ( x k , d − x k ) 2 + ( y k , d − y k ) 2 \theta _{k,d}=\mathrm{a}\tan \left( y_{k,d}-y_k,x_{k,d}-x_k \right) \\ d_k=\sqrt{\left( x_{k,d}-x_k \right) ^2+\left( y_{k,d}-y_k \right) ^2} θk,d=atan(yk,dyk,xk,dxk)dk=(xk,dxk)2+(yk,dyk)2

接着以该误差作为反馈测量值通过PID控制器生成控制量,机器人基于控制量和运动学模型运动,循环往复直到机器人完成控制目标

3 控制插件开发案例(PID算法)

不同控制器其本质区别在于 computeVelocityCommands()方法的不同,对于本文案例的PID控制器,我们的 computeVelocityCommands()接口如下:

geometry_msgs::msg::TwistStamped PIDController::computeVelocityCommands(const geometry_msgs::msg::PoseStamped& pose, const geometry_msgs::msg::Twist& speed, nav2_core::GoalChecker* goal_checker)
{...// position reachedgeometry_msgs::msg::TwistStamped cmd_vel;if (shouldRotateToGoal(current_ps_map, global_plan_.poses.back())){double e_theta = regularizeAngle(goal_rpy_.z() - theta);// orientation reachedif (!shouldRotateToPath(std::fabs(e_theta))){cmd_vel.twist.linear.x = 0.0;cmd_vel.twist.angular.z = 0.0;}// orientation not reachedelse{cmd_vel.twist.linear.x = 0.0;cmd_vel.twist.angular.z = angularRegularization(speed.angular.z, e_theta / d_t_);}}// posistion not reachedelse{Eigen::Vector3d s(current_ps_map.pose.position.x, current_ps_map.pose.position.y, theta);    // current stateEigen::Vector3d s_d(target_ps_map.pose.position.x, target_ps_map.pose.position.y, theta_d);  // desired stateEigen::Vector2d u_r(vt, wt);                                                                 // refered inputEigen::Vector2d u = _pidControl(s, s_d, u_r);cmd_vel.twist.linear.x = linearRegularization(std::hypot(speed.linear.x, speed.linear.y), u[0]);cmd_vel.twist.angular.z = angularRegularization(speed.angular.z, u[1]);}// publish next target_ps_map posetarget_ps_map.header.frame_id = "map";target_ps_map.header.stamp = current_ps_map.header.stamp;target_pose_pub_->publish(target_ps_map);// publish robot posecurrent_ps_map.header.frame_id = "map";current_ps_map.header.stamp = current_ps_map.header.stamp;current_pose_pub_->publish(current_ps_map);// populate and return messagecmd_vel.header = pose.header;return cmd_vel;
}

这里发布了两个话题target_posecurrent_pose,分别代表PID算法的目标位姿和实际位姿,二者的差值将作为误差量驱动PID控制器执行,其效果如下所示(蓝色箭头是target_pose以及绿色箭头是current_pose)

在这里插入图片描述

常见问题

  1. /opt/ros/noetic/lib/move_base/move_base: symbol lookup error: /home/winter/ROS/ros_learning_tutorials/Lecture19/devel/lib//libmy_planner.so: undefined symbol: _ZN18base_local_planner12CostmapModelC1ERKN10costmap_2d9Costmap2DE

    解决方案:未定义符号错误undefined symbol一般是依赖配置错误导致,采用c++filt工具解析符号

    c++filt _ZN18base_local_planner12CostmapModelC1ERKN10costmap_2d9Costmap2DE
    base_local_planner::CostmapModel::CostmapModel(costmap_2d::Costmap2D const&)
    

    可以看出是base_local_planner的问题,需要在功能包CMakeLists.txt中配置base_local_planner的相关依赖。

    c++filt是什么?g++编译器有名字修饰机制,其目的是给同名的重载函数不同的、唯一的签名识别,所有函数在编译后的文件中都会生成唯一的符号,c++filt可以逆向解析符号,还原函数,定位代码。

完整工程代码请联系下方博主名片获取


🔥 更多精彩专栏

  • 《ROS从入门到精通》
  • 《Pytorch深度学习实战》
  • 《机器学习强基计划》
  • 《运动规划实战精讲》

👇源码获取 · 技术交流 · 抱团学习 · 咨询分享 请联系👇

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

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

相关文章

Go 如何使用指针灵活操作内存

&#x1f49d;&#x1f49d;&#x1f49d;欢迎莅临我的博客&#xff0c;很高兴能够在这里和您见面&#xff01;希望您在这里可以感受到一份轻松愉快的氛围&#xff0c;不仅可以获得有趣的内容和知识&#xff0c;也可以畅所欲言、分享您的想法和见解。 推荐:「stormsha的主页」…

Leetcode 3196. Maximize Total Cost of Alternating Subarrays

Leetcode 3196. Maximize Total Cost of Alternating Subarrays 1. 解题思路2. 代码实现 题目链接&#xff1a;3196. Maximize Total Cost of Alternating Subarrays 1. 解题思路 这一题就是一个动态规划&#xff0c;只需要考虑每一个元素作为开始和处于序列当中的二元态即可…

深度学习引言

深度学习引言 什么是神经网络&#xff1f; 我们常常用深度学习这个术语来指训练神经网络的过程。有时它指的是特别大规模的神经网络训练。 神经网络的监督学习 关于神经网络也有很多的种类&#xff0c;考虑到它们的使用效果&#xff0c;有些使用起来恰到好处&#xff0c;但事实…

90天瘦30斤瘦身计划

90天瘦30斤瘦身计划 重要提示&#xff1a; 在开始任何减肥计划之前&#xff0c;强烈建议咨询医生或营养师以确保该计划适合您的健康状况。减肥过快可能对身体健康产生负面影响&#xff0c;因此请确保您的方法既安全又可持续。 目标&#xff1a; 在90天内健康地减轻30斤体重。…

爬虫笔记14——爬取网页数据写入MongoDB数据库,以爱奇艺为例

下载MongoDB数据库 首先&#xff0c;需要下载MongoDB数据库&#xff0c;下载的话比较简单&#xff0c;直接去官网找到想要的版本下载即可&#xff0c;具体安装过程可以看这里。 pycharm下载pymongo库 pip install pymongo然后在在python程序中我们可以这样连接MongoDB数据库…

红队内网攻防渗透:内网渗透之内网对抗:横向移动篇Kerberos委派安全非约束系约束系RBCD资源系Spooler利用

#委派安全知识点 委派是一种域内应用模式,是指将域内用户账户的权限委派给服务账号,服务账号因此能以用户的身份在域内展开活动(请求新的服务等),类似于租房中介房东的关系去理解。 域委派分类: 1、非约束委派(Unconstrained Delegation, UD) 2、约束委派(Constrained D…

【Linux】使用 rz 和 sz 命令在 Linux 中进行文件传输

那年夏天我和你躲在 这一大片宁静的海 直到后来我们都还在 对这个世界充满期待 今年冬天你已经不在 我的心空出了一块 很高兴遇见你 让我终究明白 回忆比真实精彩 &#x1f3b5; 王心凌《那年夏天宁静的海》 在 Linux 系统中&#xff0c;rz 和 sz 是两个用…

深度神经网络:解锁智能的密钥

深度神经网络&#xff1a;解锁智能的密钥 在人工智能的浩瀚星空中&#xff0c;深度神经网络&#xff08;Deep Neural Networks, DNNs&#xff09;无疑是最耀眼的那颗星。它以其强大的学习能力、高度的适应性和广泛的应用场景&#xff0c;成为了我们解锁智能世界的一把密钥。本…

[个人感悟] MySQL应该考察哪些问题?

前言 MySQL作为SQL类型基础典型, 通常会问, 索引, 事务, SQL实战 这3个部分的问题. 问题 问题-架构 能聊聊MySQL的基本架构么? MySQL支持的存储引擎有哪些, 你主要使用过哪种? 说说你的理解? 问题-索引 什么是索引? MYSQL内所有的基本种类有哪些&#xff1f;不同分类…

IPD推行成功的核心要素(十三)IPD产品开发流程让企业正确地做事情

一个公司能否成功&#xff0c;取决于它适应市场需求和竞争环境变化的速度。公司需要不断创新&#xff0c;以符合客户期望并保持相关性。这意味着需要更快速地推出新产品和改进产品。简化的产品开发流程能够支持快速开发周期&#xff0c;帮助公司领先于市场&#xff0c;用优秀的…

浏览器进程与线程(4)

上一篇&#x1f449;: 浏览器安全 文章目录 进程与线程1.进程与线程概念2.进程和线程的区别进程的特性线程的特性通信与同步 3.浏览器渲染进程中的线程4.什么是僵尸进程和孤儿进程5.死锁资源类型产生死锁的原因必要条件解决策略 6.进程通信方式7. 如何实现浏览器内多个标签页之…

植物大战僵尸杂交版2.1版本终于来啦!游戏完全免费

在这个喧嚣的城市里&#xff0c;我找到了一片神奇的绿色世界——植物大战僵尸杂交版。它不仅是一款游戏&#xff0c;更像是一扇打开自然奥秘的窗户&#xff0c;让我重新认识了植物和自然的力量。 植物大战僵尸杂交版最新绿色版下载链接&#xff1a; https://pan.quark.cn/s/d6…

如何在Rust中实现条件编译

目前正在学习使用Rust作后端开发&#xff0c;学习过程经常需要写一些调试代码&#xff0c;使用过程发现没有像#if 0 . . . #endif这样的条件编译。于是查阅资料&#xff0c;找到了替代方案&#xff0c;别说还挺好用。 目录 前言配置Cargo.toml文件代码中添加条件编译执行结果对…

MySQL的综合运用

MySQL版的葵花宝典&#xff0c;欲练此功&#xff0c;挥刀自。。。呃&#xff0c;&#xff0c;&#xff0c;说错了&#xff0c;是先创建两个表&#xff0c;分别是location表和store_info表 示例表为location表和store_info表&#xff0c;如下图所示&#xff1a; 操作一&#xf…

Layui为select绑定change事件/Layui中select绑定change事件不生效

1、问题概述&#xff1f; 在使用jQuery的时候&#xff0c;我们可以通过如下方式为select下拉框绑定change事件&#xff0c;但是在layui中不生效。 所以经常有人发问&#xff1a;Layui中为select绑定change事件不生效。 $(function(){//通过id为select绑定change事件$("…

【C++高阶】掌握AVL树:构建与维护平衡二叉搜索树的艺术

&#x1f4dd;个人主页&#x1f339;&#xff1a;Eternity._ ⏩收录专栏⏪&#xff1a;C “ 登神长阶 ” &#x1f921;往期回顾&#x1f921;&#xff1a;STL-> map与set &#x1f339;&#x1f339;期待您的关注 &#x1f339;&#x1f339; ❀AVL树 &#x1f4d2;1. AVL树…

mysql5.7升级到mysql8.0遇坑

mysql5.7升级到mysql8.0发现生产环境服务会报错 Error querying database. Cause: java.sql.SQLSyntaxErrorException: FUNCTION GeomFromText does not exist 在MySQL 8.0中&#xff0c;GeomFromText函数已经被弃用&#xff0c;取而代之的是ST_GeomFromText函数。你可以将你…

JavaSE (Java基础):运算符

3 运算符 3.1 二元运算符 为什么下面这段代码中最后的语句中b元素要加&#xff08;double&#xff09;呢&#xff1f; 因为要计算10/40的话&#xff0c;他们都是int类型的在计算机中会取整&#xff0c;而计算机取整一般都是直接舍去小数点后面的数字&#xff0c;那么就会返回0&…

服务端渲染(SSR)

服务端渲染&#xff08;SSR&#xff09; 服务端渲染&#xff08;Server-Side Rendering, SSR&#xff09;是一种网页开发技术&#xff0c;它允许前端应用程序的部分或全部内容在服务器端被生成为HTML&#xff0c;然后发送到客户端浏览器中展示。这样做的主要目标是提供更好的初…

VScode基本使用

VScode下载安装&#xff1a; Visual Studio Code - Code Editing. Redefined MinGW的下载安装&#xff1a; MinGW-w64 - for 32 and 64 bit Windows - Browse Files at SourceForge.net x86是64位处理器架构&#xff0c;i686是32为处理器架构。 POSIX和Win32是两种不同的操…