ROS c++ 编写动态调参(dynamic reconfigure)客户端,导航参数程序动态调节,以dwa_local_planner为例

需求说明

在室内服务机器人的导航中,大多数不需要过低的目标点位姿容差,只在一些特殊点位需要低位姿容差比如充电站。对此dwa局部路径规划器中的xy_goal_tolerance、yaw_goal_tolerance在平常的巡航中可以相对较高,当机器人判断需要回充电站时,在程序中调节对应的参数,不需要人为的在rqt_reconfigure工具中调节。


目录

需求说明

无回调函数

有回调函数

通过类来加载


注意

  • 以下cpp需要在CMakeilsts.txt中添加依赖dynamic_reconfigure
find_package(catkin REQUIRED
    dynamic_reconfigure
)
  • 查看你的动态参数节点名称:运行动态参数服务端节点
    rosrun dynamic_reconfigure dynparam list

无回调函数

#include "ros/ros.h"
#include "dwa_local_planner/DWAPlannerConfig.h" 
/*可以根据需要替换不同的Config头文件
#include "move_base/MoveBaseConfig.h"
#include "base_local_planner/BaseLocalPlannerConfig.h"
#include "global_planner/GlobalPlannerConfig.h"
#include "costmap_2d/Costmap2DConfig.h"
#include "costmap_2d/InflationPluginConfig.h"
...
*/

//dynamic_reconfigure客户端头文件
#include "dynamic_reconfigure/client.h" 

int main(int argc, char **argv)
{
    ros::init(argc, argv, "dwa_dynamic_reconfigure");
//声明定义一个动态调参客户端
//dynamic_reconfigure::Client<根据选择的Congfig头文件来填写>,
//client("根据动态参数节点名来填写")
    dynamic_reconfigure::Client<dwa_local_planner::DWAPlannerConfig> client("/move_base/DWAPlannerROS");
    //声明一个动态参数对象
    dwa_local_planner::DWAPlannerConfig dwa_config;
    ros::Rate loop_rate(5);
    while (ros::ok())
    {
     //等待在1s,获取最新的配置   
     client.getCurrentConfiguration(dwa_config,ros::Duration(1));
     if(dwa_config.xy_goal_tolerance > 0.1 && dwa_config.yaw_goal_tolerance >0.05) {
       dwa_config.xy_goal_tolerance = 0.1;
       dwa_config.yaw_goal_tolerance =0.05;
       ROS_INFO("double: %f, double: %f", dwa_config.xy_goal_tolerance, dwa_config.yaw_goal_tolerance);
       //设置配置参数     若没有通过getCurrentConfiguration先获取配置,则需要重新为每一个参数对象里的全部参数赋值
       client.setConfiguration(dwa_config);
       break;
     }
      ros::spinOnce();
      loop_rate.sleep();
    }
    return 0;
}

有回调函数

#include "ros/ros.h"
#include "dwa_local_planner/DWAPlannerConfig.h" 
/*可以根据需要替换不同的Config头文件
#include "move_base/MoveBaseConfig.h"
#include "base_local_planner/BaseLocalPlannerConfig.h"
#include "global_planner/GlobalPlannerConfig.h"
#include "costmap_2d/Costmap2DConfig.h"
#include "costmap_2d/InflationPluginConfig.h"
...
*/

//dynamic_reconfigure客户端头文件
#include "dynamic_reconfigure/client.h" 

//当服务器通知客户端成功重新配置时的回调函数
void config_callback(const dwa_local_planner::DWAPlannerConfig &dwa_config)
{
     ROS_INFO("a successful reconfiguration");
     ROS_INFO("xy_goal_tolerance: %.2f, yaw_goal_tolerance: %.2f", dwa_config.xy_goal_tolerance, dwa_config.yaw_goal_tolerance);
}
//当服务器向客户端通知重新配置参数和组的描述时的回调函数
void description_callback(const dwa_local_planner::DWAPlannerConfig &dwa_config)
{
    ROS_INFO("the reconfiguration parameters and groups");
}
int main(int argc, char **argv)
{
    ros::init(argc, argv, "dwa_dynamic_reconfigure");
//声明定义一个动态调参客户端
//dynamic_reconfigure::Client<根据选择的Congfig头文件来填写>,
//client("根据动态参数节点名来填写")
    dynamic_reconfigure::Client<dwa_local_planner::DWAPlannerConfig> client("/move_base/DWAPlannerROS",config_callback,description_callback);
    //声明一个动态参数对象
    dwa_local_planner::DWAPlannerConfig dwa_config;
    ros::Rate loop_rate(5);
    while (ros::ok())
    {
     //等待在1s,获取最新的配置   
     client.getCurrentConfiguration(dwa_config,ros::Duration(1));
     if(dwa_config.xy_goal_tolerance > 0.1 && dwa_config.yaw_goal_tolerance >0.05) {
       dwa_config.xy_goal_tolerance = 0.1;
       dwa_config.yaw_goal_tolerance =0.05;
       ROS_INFO("xy_goal_tolerance: %.2f, yaw_goal_tolerance: %.2f", dwa_config.xy_goal_tolerance, dwa_config.yaw_goal_tolerance);
       //设置配置参数     若没有通过getCurrentConfiguration先获取配置,则需要重新为每一个参数对象里的全部参数赋值
       client.setConfiguration(dwa_config);
       break;
     }
      ros::spinOnce();
      loop_rate.sleep();
    }
    return 0;
}

通过类来加载

#include "ros/ros.h"
#include "std_msgs/Bool.h"
#include "dwa_local_planner/DWAPlannerConfig.h" 
/*可以根据需要替换不同的Config头文件
#include "move_base/MoveBaseConfig.h"
#include "base_local_planner/BaseLocalPlannerConfig.h"
#include "global_planner/GlobalPlannerConfig.h"
#include "costmap_2d/Costmap2DConfig.h"
#include "costmap_2d/InflationPluginConfig.h"
...
*/

//dynamic_reconfigure客户端头文件
#include "dynamic_reconfigure/client.h" 

class A
{
public:
  A():client("/move_base/DWAPlannerROS",
           boost::bind(&A::configurationCallback,this,_1)) {
    sub_go_home=nh.subscribe("/gohome",100,&A::GoHomeCallback,this);
  }
  void GoHomeCallback(const std_msgs::Bool::ConstPtr &msg);
  void configurationCallback(const dwa_local_planner::DWAPlannerConfig &config);
private:
  ros::NodeHandle nh;
  ros::Subscriber sub_go_home;
  dwa_local_planner::DWAPlannerConfig dwa_config;
  dynamic_reconfigure::Client<dwa_local_planner::DWAPlannerConfig> client;
};

void A::configurationCallback(const dwa_local_planner::DWAPlannerConfig &config)
{
  ROS_INFO("a successful reconfiguration");
}
void A::GoHomeCallback(const std_msgs::Bool::ConstPtr &msg)
{
  if(msg->data == true) {
    client.getCurrentConfiguration(dwa_config,ros::Duration(1));
      if(dwa_config.xy_goal_tolerance > 0.1 && dwa_config.yaw_goal_tolerance >0.05) {
        dwa_config.xy_goal_tolerance = 0.1;
        dwa_config.yaw_goal_tolerance =0.05;
        ROS_INFO("xy_goal_tolerance: %.2f, yaw_goal_tolerance: %.2f", dwa_config.xy_goal_tolerance, dwa_config.yaw_goal_tolerance);
        client.setConfiguration(dwa_config);
      }
  }
}
int main(int argc, char **argv)
{
    ros::init(argc, argv, "dwa_dynamic_reconfigure");
    A oa;
    ros::spin();
    return 0;
}

欢迎大家一起交流

  • 5
    点赞
  • 24
    收藏
    觉得还不错? 一键收藏
  • 2
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 2
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值