本文参考于:https://blog.csdn.net/u014610460/article/details/79531616#commentBox
目前官网给出的例程实现dynamic_reconfigure的客户端只给出了python例程,而服务端给了c++和python两种方法的实现。
后来查看了下dynamic_reconfigure的源码,发现在头文件中包含了client.h文件,仔细研究了下,并对比了server.h文件,发现包含该文件即可用C++实现dynamic_reconfigure的客户端。
服务端 :python 、C++
客户端:python,现在要自己写一个C++的
另外的例子:https://www.corvin.cn/651.html
演示:控制旋转的速度
代码:
1、cfg文件 (记得赋权)
#!/usr/bin/env python
# _*_ coding:utf-8 _*_
PACKAGE = "dynamic_reconfigure_pid"
from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
gen.add("cmd_topic", str_t, 0, "turtlesim cmd topic name", "/turtle1/cmd_vel")
gen.add("cmd_pub_rate", int_t, 0, "turtlesim cmd pub rate", 1, 0, 5)
gen.add("linear_x", double_t, 0, "turtlesim linear.x", 1.0, 0.5, 3.0)
gen.add("angular_z", double_t, 0, "turtlesim angular.z", 1.0, 0.5, 3.0)
gen.add("move_flag", bool_t, 0, "turtlesim whether move or not", True )
log_enum = gen.enum([ gen.const("info", int_t, 0, "log print flag:INFO"),
gen.const("warn", int_t, 1, "log print flag:WARN"),
gen.const("error", int_t, 2, "log print flag:ERROR")],
"Set Log Level")
gen.add("log_level", int_t, 0, "Set Log Level", 0, 0, 2, edit_method=log_enum)
exit(gen.generate(PACKAGE, "turtlesim_dynamic_node", "dynamic"))
exit()用于生成所有C++和Python相关的文件并且退出程序,这里第二个参数表示动态参数运行的节点名,第三个参数是生成文件所使用的前缀,需要和配置文件名相同。
2、turtlesim_dynamic.cpp
#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include <dynamic_reconfigure/server.h>
#include <dynamic_reconfigure_pid/dynamicConfig.h>
using namespace std;
string cmd_topic = "/turtle1/cmd_vel";
int loop_rate = 1;
double linear_x = 1.0;
double angular_z = 1.0;
bool move_flag = true;
int log_level= 0;
void dynamic_callback(turtlesim_dynamic::dynamicConfig &config)
{
ROS_INFO("Reconfigure Request: %s %d %f %f %s %d",
config.cmd_topic.c_str(),
config.cmd_pub_rate,
config.linear_x,
config.angular_z,
config.move_flag?"True":"False",
config.log_level);
cmd_topic = config.cmd_topic;
loop_rate = config.cmd_pub_rate;
linear_x = config.linear_x;
angular_z = config.angular_z;
move_flag = config.move_flag;
log_level = config.log_level;
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "turtlesim_dynamic_node");
ros::NodeHandle handle;
dynamic_reconfigure::Server<turtlesim_dynamic::dynamicConfig> server;
dynamic_reconfigure::Server<turtlesim_dynamic::dynamicConfig>::CallbackType callback;
callback = boost::bind(&dynamic_callback, _1);
server.setCallback(callback);
ros::Publisher cmdVelPub;
geometry_msgs::Twist speed;
while(ros::ok())
{
cmdVelPub = handle.advertise<geometry_msgs::Twist>(cmd_topic, 1);
ros::Rate rate(loop_rate);
if(move_flag)
{
speed.linear.x = linear_x;
speed.angular.z = angular_z;
cmdVelPub.publish(speed);
switch(log_level)
{
case 0:
ROS_INFO("log level: INFO, cmd_pub_rate: %d", loop_rate);
break;
case 1:
ROS_WARN("log level: WARN, cmd_pub_rate: %d", loop_rate);
break;
case 2:
ROS_ERROR("log level: ERROR, cmd_pub_rate: %d", loop_rate);
break;
default:
break;
}
}
ros::spinOnce();
rate.sleep();
}
}
3、CMakeLists.txt (修改的地方)
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
dynamic_reconfigure
)
generate_dynamic_reconfigure_options(
cfg/dynamic.cfg
)
add_executable(turtlesim_dynamic_node src/turtlesim_dynamic.cpp)
add_dependencies(turtlesim_dynamic_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(turtlesim_dynamic_node ${catkin_LIBRARIES})
4、turtlesim_dynamic.launch
<launch>
<node pkg="turtlesim" type="turtlesim_node" name="turtlesim_node" output="screen" />
<node pkg="dynamic_reconfigure_pid" type="turtlesim_dynamic_node" name="turtlesim_dynamic_node" output="screen" />
<node pkg="rqt_reconfigure" type="rqt_reconfigure" name="rqt_reconfigure" output="screen" />
</launch>
5、运行:roslaunch dynamic_reconfigure_pid turtlesim_dynamic.launch
可以参考着写一个调节PID的例子
PS:别人的一个界面,没有代码,可以看看