本实验主要学习以下几方面的内容:
1.所需仪器设备
(1)“卓越之星”设备-用于功能调试;
(2)个人PC-用于应用程序的开发与展示;
2.注意事项
(1)个人PC需要安装NoMachine或者VSCode支持远程编程开发;
(2)运动实验尽可能将设备平放在地面上;
(3)实验开始前确保设备电量为满电,实验完成后关闭设备电源;
在 ROS
参数服务器中,参数的变化是异步的,即某个参数的变化并不会通知到使用这个参数的节点(该节点自己主动查询除外),这就给参数的使用造成了很大的局限性。有些时候,我们需要改变一个参数的时候,使用这个参数的节点可以马上获取参数并改变运行策略,这时就需要一种新的通讯方式满足使用需求。ROS
动态参数功能可以满足此需求。
ROS(Robot Operating System)的动态参数是一种可以在运行时调整和修改的系统参数。这些参数可以通过动态参数服务器进行配置,而不需要修改源代码或重新编译程序。
动态参数可以通过 ROS 的命令行工具或 GUI 工具进行配置,使得用户可以实时地调整系统参数,以适应不同的应用场景或调试需求。同时,动态参数也支持参数的保存和加载,方便用户在不同实验或任务之间共享参数配置。
在 ROS 中,动态参数的实现依赖于 dynamic_reconfigure 包,该包提供了一种用于生成动态参数配置界面的机制。通过编写 cfg
文件,用户可以定义需要配置的参数及其属性,然后通过 dynamic_reconfigure 生成器生成配置界面。这样,用户就可以通过界面实时地调整参数,并获取参数的当前值。
动态参数配置的核心原理是提供一种标准的方法,将节点的一个子集参数(你想要动态调试那一部分参数)公开给外部重配置。使用客户端程序,例如
GUI,可以向节点查询一组可动态配置的参数,包括它们的名称、类型、范围,并向用户提供一个自定义接口。
ROS 配置动态参数的步骤一般如下:
创建一个功能包,包含需要配置动态参数的节点程序。
catkin_create_pkg class_7_pkg rospy roscpp dynamic_reconfigure
在功能包中创建一个 cfg 文件夹,用于存放配置文件。
在 cfg 文件夹中创建一个 cfg 文件,定义需要配置的参数及其属性。
#!/usr/bin/env python3
PACKAGE = "class_7_pkg"
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", 0.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, "class_7_pkg", "Tutorials"))
我们来详细解析一下上述文件,动态配置 C/S 服务通信的架构中客户端是基于
XXX.cfg 文件实现,其实就是基于 Python
的语法。
导入 dynamic_reconfigure 功能包提供的参数生成器(parameter generator)函数库:
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)
参数可以使用生成器的 add(name, type, level, description, default, min, max)方法生成,这里定义了四个不同类型的参数,传入参数的意义如下:
name:参数名,使用字符串描述;
type:定义参数的类型,可以是 int_t,double_t,str_t,或者 bool_t;
level:参数动态配置回调函数中的掩码,在回调函数中会修改所有参数的掩码,表示参数已经被修改;
description:描述参数作用的字符串;
default:设置参数的默认值;
min:可选,设置参数的最小值,对于字符串和布尔类型值不生效;
也可以使用如下方法生成一个枚举类型的值:
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)
这里定义了一个 int_t 类型的参数“size”,该参数的值可以通过一个枚举罗列出来。枚举的定义使用 enum 方法实现,其中使用
const()方法定义每一个枚举值的名称、类型、值和描述字符串。
生成所有 C++和 Python 相关的文件,并且退出程序。第二个参数表示运行时的节点名,第三个参数是生成文件所使用的前缀,需要和配置文件名相同:
exit(gen.generate(PACKAGE,"class_7_pkg", "Tutorials"))
配置文件创建完成后,需要使用如下命令添加可执行权限:
当编写完cfg 文件之后,一定要开启以下 Linux 系统中关于 python 脚本文件的可执行权限,只有基于脚本可执行权限,编译才可以通过,才可以生成
GUI。
chmod a+x cfg/Tutorials.cfg
在 CMakeLists.txt 中添加如下编译规则:
#add dynamic reconfigure api
generate_dynamic_reconfigure_options(
cfg/Tutorials.cfg
#...
)
# make sure configure headers are built before any node using them
add_dependencies(dynamic_reconfigure_node ${PROJECT_NAME}_gencfg)
编译此功能包,然后创建一个 dynamic_reconfigure_node 节点,调用参数的动态配置。
这里我们创建一个动态参数的节点,代码如下:
#include <ros/ros.h>
//包含必要的头文件,其中TutorialsConfig.h就是配置文件在编译过程中生成的头文件。
#include <dynamic_reconfigure/server.h>
#include <class_7_pkg/TutorialsConfig.h>
//定义回调函数,并将回调函数和服务端绑定。当客户端请求修改参数时,服务端即可跳转到回调函数进行处理
void callback(class_7_pkg::TutorialsConfig &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, "dynamic_tutorials");
//创建了一个参数动态配置的服务端实例
//参数配置的类型与配置文件中描述的类型相同
dynamic_reconfigure::Server<class_7_pkg::TutorialsConfig> server;
dynamic_reconfigure::Server<class_7_pkg::TutorialsConfig>::CallbackType f;
//绑定回调
f = boost::bind(&callback, _1, _2);
server.setCallback(f);
ROS_INFO("Spinning node");
ros::spin();
return 0;
}
本例程来说,回调函数并不复杂,仅将修改后的参数值打印出来。回调函数的传入参数有两个,一个是参数更新的配置值,另外一个表示参数修改的掩码。
代码编辑完成后,在 CmakeLists.txt 中加入以下编译规则:
add_executable(dynamic_reconfigure_node src/dynamic_reconfigure.cpp)
# make sure configure headers are built before any node using them
add_dependencies(dynamic_reconfigure_node ${PROJECT_NAME}_gencfg)
# for dynamic reconfigure
target_link_libraries(dynamic_reconfigure_node ${catkin_LIBRARIES})
现在就可以使用 catkin_make 命令编译 class_7_pkg 功能包了。
编译成功后使用如下命令将 roscore 和 dynamic_reconfigure_node 运行起来:
rosrun dynamic_tutorials dynamic_reconfigure_node
这个时候参数动态配置的服务端就运行起来了,使用 ROS 提供的可视化参数配置工具来修改参数:
rosrun rqt_reconfigure rqt_reconfigure
打开如下图所示的可视化界面后,可以通过输入、拖动、下拉选择等方式动态修改参数,输入方式的不同和配置文件中的参数设置有关,例如设置了参数的最大最小值,就会有拖动条;设置为枚举类型,就会出现下拉选项。
修改后可以在服务端中看到修改成功的打印信息。
接下来,我们实现动态配置机器人的运动速度,设置一个double类型的动态参数,上下限分别为(-0.25~
0.25),在动态参数服务器中配置此速度,机器人动态的调节运行速度,代码如下所示,可以订阅/cmd_vel这个消息来观察动态参数调节的结果:
#include <ros/ros.h>
//包含必要的头文件,其中TutorialsConfig.h就是配置文件在编译过程中生成的头文件。
#include <dynamic_reconfigure/server.h>
#include <class_7_pkg/TutorialsConfig.h>
#include <geometry_msgs/Twist.h>
double robot_speed = 0;
//定义回调函数,并将回调函数和服务端绑定。当客户端请求修改参数时,服务端即可跳转到回调函数进行处理
void callback(class_7_pkg::TutorialsConfig &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);
robot_speed = config.double_param;
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "dynamic_tutorials");
//创建了一个参数动态配置的服务端实例
//参数配置的类型与配置文件中描述的类型相同
ros::NodeHandle(nh);
dynamic_reconfigure::Server<class_7_pkg::TutorialsConfig> server;
dynamic_reconfigure::Server<class_7_pkg::TutorialsConfig>::CallbackType f;
ros::Publisher cmd_pub_ = nh.advertise<geometry_msgs::Twist>("/cmd_vel", 10);
//绑定回调
f = boost::bind(&callback, _1, _2);
server.setCallback(f);
ROS_INFO("Spinning node");
ros::Rate rate(10);
while(ros::ok())
{
geometry_msgs::Twist cmd_vel;
cmd_vel.linear.x = 0.1;
cmd_pub_.publish(cmd_vel);
ros::spinOnce();
rate.sleep();
}
return 0;
}