ROS基础 - dynamic_reconfigure 动态参数使用 实例详解

ROS基础 - dynamic_reconfigure 动态参数使用 实例详解

采用 ROS::dynamic_reconfigure 的形式, 可以在程序运行过程中实时更改参数大小,C++代码通过回调函数接收数据,实在是仿真中的一件利器,强烈推荐。
注意:cfg文件要更改执行权限。

主要步骤如下:
1、src/frame_pub/cfg/paramDynamicConfig.cfg文件编写
2、src/frame_pub/src/frame_pub.cpp 文件编写
3、src/frame_pub/CMakeLists.txt 文件编写
4、src/frame_pub/package.xml 文件编写

1、src/frame_pub/cfg/paramDynamicConfig.cfg文件编写

文件采用python编写。

#!/usr/bin/env python
PACKAGE =   "frame_pub"
from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()

gen.add("int_param",    int_t,    0, "An Integer parameter", 50,  0, 100)
gen.add("double_param", double_t, 0, "A double parameter",    .5, 0,   1)
gen.add("str_param",    str_t,    0, "A string parameter",  "Hello World")
gen.add("bool_param",   bool_t,   0, "A Boolean parameter",  True)
gen.add("StopMove",   bool_t,   0, "A Boolean parameter",  False)

size_enum = gen.enum([ gen.const("Small",      int_t, 0, "A small constant"),
            gen.const("Medium",     int_t, 1, "A medium constant"),
            gen.const("Large",      int_t, 2, "A large constant"),
            gen.const("ExtraLarge", int_t, 3, "An extra large constant")],
            "An enum to set size")

gen.add("size", int_t, 0, "A size parameter which is edited via an enum", 1, 0, 3, edit_method=size_enum)

exit(gen.generate(PACKAGE, "frame_pub", "frame_pub"))

PACKAGE: 需要和创建的功能包名字相同,详见CMakeLists.txt文件中的 project(frame_pub)

gen.add函数: 表示添加需要修改的参数(name, type, level, description, default, min, max)。

exit: 第三个参数表示生成的头文件名称,本例子中为frame_pub,则生成的头文件名称为 frame_pubConfig.h ,生成的头文件在/devel/include下面可以查看到。
注意:通过exit生成.h文件,需要在CMakelists中增加如下代码:

  generate_dynamic_reconfigure_options(cfg/paramDynamicConfig.cfg)

注意:
generate_dynamic_reconfigure_options() must be called before catkin_package()
generate_dynamic_reconfigure_options() 必须放到catkin_package()之前。

2、src/frame_pub/src/frame_pub.cpp 文件编写

#include <ros/ros.h>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2/LinearMath/Quaternion.h>

#include <dynamic_reconfigure/server.h>
#include "frame_pub/frame_pubConfig.h"

float fSpeed = 0.00;

void callback(frame_pub::frame_pubConfig &config, uint32_t level)
{
    ROS_INFO("ROS INFO: Reconfigure Request: %d %f %s %s %d \n",
             config.int_param, config.double_param,
             config.str_param.c_str(),
             config.bool_param?"True":"False",
             config.size);

    printf("printf Info: Reconfigure Request: *.int_param = [%d] *.double_param[%f] *.str_param = [%s] \n",
           config.int_param, config.double_param,
           config.str_param.c_str());

    printf("printf Info: Reconfigure Request: *.bool_param =[%s], *.StopMove = [%s], *.size = [%d] \n",
           config.bool_param?"True":"False",
           config.StopMove?"True":"False",
           config.size);

    //iSpeed = config.int_param;
    fSpeed = config.StopMove ? 0.01 : 0.00;
    printf("fSpeed = %f \n", fSpeed);
}


int main(int argc, char** argv)
{
  ros::init(argc, argv, "my_tf2_broadcaster");

  dynamic_reconfigure::Server<frame_pub::frame_pubConfig> server;
  dynamic_reconfigure::Server<frame_pub::frame_pubConfig>::CallbackType f;
  f = boost::bind(&callback,_1,_2);
  server.setCallback(f);
  ROS_INFO("spinning node \n");

  ros::NodeHandle node;

  tf2_ros::TransformBroadcaster tfb;
  geometry_msgs::TransformStamped transformStamped;

  transformStamped.header.frame_id = "base_link";
  transformStamped.child_frame_id = "fps";
  transformStamped.transform.translation.x = 16.0;
  transformStamped.transform.translation.y = 2.5;
  transformStamped.transform.translation.z = 3.0;
  tf2::Quaternion q;
  q.setRPY(0, 0, 0);
  transformStamped.transform.rotation.x = q.x();
  transformStamped.transform.rotation.y = q.y();
  transformStamped.transform.rotation.z = q.z();
  transformStamped.transform.rotation.w = q.w();
  q.x();
  transformStamped.transform.rotation.y = q.y();
  transformStamped.transform.rotation.z = q.z();
  transformStamped.transform.rotation.w = q.w();

  printf("Begin\n");
  ros::Rate rate(1000.0);
  while (node.ok())
  {
    transformStamped.header.stamp = ros::Time::now();
    transformStamped.transform.translation.x += fSpeed; //0.01;
    tfb.sendTransform(transformStamped);
    rate.sleep();
    printf("fSpeed = %f \n", fSpeed);
    //printf("sending\n");
    ros::spinOnce(); //执行回调需要此处理!!!
  }

    printf("Exit\n");
}

3、src/frame_pub/CMakeLists.txt 文件编写

cmake_minimum_required(VERSION 3.0.2)
project(frame_pub)
find_package(catkin REQUIRED COMPONENTS
  roscpp
  tf2
  tf2_ros
  dynamic_reconfigure
)
generate_dynamic_reconfigure_options(cfg/paramDynamicConfig.cfg)
catkin_package()
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
  ../../devel/include  #note: new add
  ${catkin_INCLUDE_DIRS}
)
add_executable(frame_pub src/frame_pub.cpp)

## Specify libraries to link a library or executable target against
target_link_libraries(frame_pub
  ${catkin_LIBRARIES}
)

注意:include_directories中增加了 …/…/devel/include ,否则在编写代码时,引用头文件 “#include <frame_pub/frame_pubConfig.h>” 会显示波浪线。 且头文件中的 相关结构 也会提示红色字体,认为是未识别。但其实是可以编译通过的。 建议在CMakeList.txt中,增加 “ …/…/devel/include”

注意: 这里的 dynamic_reconfigure,否则后面的generate_dynamic_reconfigure_options会报错: Unknown CMake command “generate_dynamic_reconfigure_options”

4、src/frame_pub/package.xml 文件编写

<?xml version="1.0"?>
<package format="2">
  <name>frame_pub</name>
  <version>0.0.0</version>
  <description>The frame_pub package</description>
  <maintainer email="waytous@todo.todo">waytous</maintainer>
  <license>TODO</license>
  <buildtool_depend>catkin</buildtool_depend>
  <build_depend>roscpp</build_depend>
  <build_depend>tf2</build_depend>
  <build_depend>dynamic_reconfigure</build_depend>
  <build_export_depend>roscpp</build_export_depend>
  <build_export_depend>tf2</build_export_depend>
  <exec_depend>roscpp</exec_depend>
  <exec_depend>tf2</exec_depend>
  <export>
    <!-- Other tools can request additional information be placed here -->
  </export>
</package>

注意其中的:
<build_depend>roscpp</build_depend>
<build_depend>tf2</build_depend>

5、运行

首先启动 roscore , 然后启动 rosrun 节点, 最后启动rosrun rqt_reconfigure rqt_reconfigure。

roscore
source devel/setup.bash 
rosrun frame_pub frame_pub
rosrun rqt_reconfigure rqt_reconfigure

注意:source 命令要在 代码根目录下,通常与devel、src同级目录

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

Adunn

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

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

余额充值