初始参数设置
有两种方法设置初始参数:
-
一个通过launch文件来设置
https://blog.csdn.net/weixin_42587961/article/details/86649031
-
一个通过命令行来设置
例如:
roslaunch aruco_ros single.launch markerId:=26 markerSize:=0.08 eye:="right"
参数动态配置
动态重配置参数:就是动态地调整、设置正在运行的节点的参数值(它们允许用户不仅在启动时修改变量,还能在运行过程中修改变量。我们已经创建了一个文件中指定的变量可动态重新配置服务器。),通过动态重配置,可以更加高效地开发和测试节点,特别是机器人硬件调试的时候,使用动态重配置参数是一个很不错的选择.
1.向功能包添加动态重配置文件(.cfg)
#本文中pakeage是test
roscd test
mkdir cfg && cd cfg
gedit Tutorials.cfg
输入如下的内容:
#!/usr/bin/env python
PACKAGE = "dynamic_reconfigure"
from dynamic_reconfigure.parameter_generator_catkin import *
gen =ParameterGenerator() #创建一个参数生成器对象
#gen.add(参数名称,参数类型,位掩码,参数描述,默认值,最小值,最大值)
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)
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, "test", "Tutorials"))
#first parameter is namespace's name
#second parameter is node's name
#third parameter is the current file's name
2.修改CMakeLists.txt文件
cmake_minimum_required(VERSION 2.8.3)
project(test)
find_package(catkin REQUIRED
COMPONENTS roscpp std_msgs dynamic_reconfigure
)
generate_dynamic_reconfigure_options( cfg/Tutorials.cfg )
catkin_package( LIBRARIES custom_dynamic_reconfigure
CATKIN_DEPENDS roscpp std_msgs dynamic_reconfigure
)
include_directories(${catkin_INCLUDE_DIRS})
add_dependencies({PROJECT_NAME}_node ${PROJECT_NAME}_gencfg) #添加依赖性也很关键,否则找不到生成的*Config.h文件
3.修改package.xml文件
增加
<depend>dynamic_reconfigure</depend>
4.修改cfg文件的权限
chmod a+x Tutorials.cfg(或 chmod 777 Tutorials.cfg)
5.编辑cpp文件
服务端
#include "ros/ros.h"
#include <dynamic_reconfigure/server.h>
#include <test/Tutorials.h>
void callback(test::Tutorials &config, uint32_t level)
{
ROS_INFO("Reconfigure Request: %d %f %s %s %d",
config.int_param,
config.double_param,
config.str_param.c_str(),
config.bool_param?"True":"False",
config.size);
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "node_e_dynamic_reconfigure");
dynamic_reconfigure::Server<test::Tutorials> server;
dynamic_reconfigure::Server<test::Tutorials>::CallbackType f;
f = boost::bind(&callback, _1, _2);//绑定回调函数
//为服务器设置回调函数, 节点程序运行时会调用一次回调函数来输出当前的参数配置情况
server.setCallback(f);
ros::spin();
return 0;
}
客户端
#include "ros/ros.h"
#include <dynamic_reconfigure/server.h>
#include <test/Tutorials.h>
int main(int argc, char **argv)
{
dynamic_reconfigure::Client<test::Tutorials> client("dynamic_srv", dynCallBack); //订阅服务,并设置回调函数用于回读改变后的最新参数
test::Tutorials config;
ros::Rate loop_rate(10);
while (ros::ok())
{
static bool ret = true;
static int cnt = 0;
config.bool_param = !ret;
config.int_param = cnt;
config.double_param = 1/((double)(cnt+1));
client.setConfiguration(config); //用于更新参数
ret = !ret;
ros::spinOnce();
loop_rate.sleep();
}
}
rosrun rqt_reconfigure rqt_reconfigure
运行后会有一个新窗口,可以动态重配置节点的参数
参考:《ROS机器人高效编程》(原书第3版)https://github.com/rosbook/effective_robotics_programming_with_ros