ROS動態引數伺服器
ros動態引數在官方叫做dynamic_reconfigure,這個功能的作用是用於node執行時修改內部引數,區別於靜態讀取本地yaml檔案引數的方式(更常用),請見另一github倉庫。
主要用途是在除錯機器人時能動態修改機器人參數,而不需要重新編譯。
具體操作流程:
1、建立一個cfg檔案(python檔案),裡面定義引數,說白了就像是一個自定義msg。
2、編譯功能包,ros會幫我們生成cfg檔案的cpp和py檔案,以供呼叫。所以說和自定義msg很像。
3、編寫當cfg檔案引數修改時的回撥函式。
4、使用rqt_reconfigure圖形化介面修改cfg檔案引數,檢視結果。
說實話,著用起來是真的很麻煩,ros門檻是真多。
建立cfg檔案
新建功能包依賴於roscpp, rospy, dynamic_reconfigure。
cfg檔案支援,int,double,string,bool,列舉資料型別
建立cfg/mycar.cfg檔案
"""
生成動態引數 int,double,bool,string,列舉
實現流程:
1.導包
2.建立生成器
3.向生成器新增若干引數
4.生成中間檔案並退出
"""
# 1.導包
from dynamic_reconfigure.parameter_generator_catkin import *
PACKAGE = "learning_dynamic_reconfigure"
# 2.建立生成器
gen = ParameterGenerator()
# 3.向生成器新增若干引數
#add(name, paramtype, level, description, default=None, min=None, max=None, edit_method="")
gen.add("int_param",int_t,0,"整型引數",50,0,100)
gen.add("double_param",double_t,0,"浮點引數",1.57,0,3.14)
gen.add("string_param",str_t,0,"字串引數","hello world ")
gen.add("bool_param",bool_t,0,"bool引數",True)
many_enum = gen.enum([gen.const("small",int_t,0,"a small size"),
gen.const("mediun",int_t,1,"a medium size"),
gen.const("big",int_t,2,"a big size")
],"a car size set")# 列舉型別
gen.add("list_param",int_t,0,"列舉引數",0,0,2, edit_method=many_enum)
# 4.生成中間檔案並退出
exit(gen.generate(PACKAGE,"dr_node","mycar")) #注意最後一個引數必須是cfg檔名
編譯cfg檔案
mycar.cfg檔案其實就是一個py檔案,ros編譯後生成對應的cpp和py的標頭檔案,分別在devel/include和devel/lib下面。
#cmakelists.txt修改
generate_dynamic_reconfigure_options(
cfg/mycar.cfg
)
catkin_make編譯後,會在devel/include生成對應的cpp標頭檔案,以xxxConfig.h結尾,在devel/lib/python3下面生成python的呼叫檔案,以xxxConfig.py結尾。
編寫回撥函式
當引數值發生變化時觸發回撥函式。
建立src/use_dr.cpp檔案
#include "dynamic_reconfigure/server.h"
#include "learning_dynamic_reconfigure/mycarConfig.h"
#include "ros/ros.h"
/*
動態引數服務端: 引數被修改時直接列印
實現流程:
1.包含標頭檔案
2.初始化 ros 節點
3.建立伺服器物件
4.建立回撥物件(使用回撥函式,列印修改後的引數)
5.伺服器物件呼叫回撥物件
6.spin()
*/
void cb(learning_dynamic_reconfigure::mycarConfig& config, uint32_t level) {
ROS_INFO("動態引數解析資料:%d,%.2f,%d,%s,%d", config.int_param,
config.double_param, config.bool_param, config.string_param.c_str(),
config.list_param);
}
int main(int argc, char* argv[]) {
setlocale(LC_ALL, "");
// 2.初始化 ros 節點
ros::init(argc, argv, "dr");
// 3.建立伺服器物件
dynamic_reconfigure::Server<learning_dynamic_reconfigure::mycarConfig> server;
// 4.建立回撥物件(使用回撥函式,列印修改後的引數)
dynamic_reconfigure::Server<
learning_dynamic_reconfigure::mycarConfig>::CallbackType cbType;
cbType = boost::bind(&cb, _1, _2);
// 5.伺服器物件呼叫回撥物件
server.setCallback(cbType);
// 6.spin()
ros::spin();
return 0;
}
cmakelists.txt檔案
add_executable(use_dr_node src/use_dr.cpp)
target_link_libraries(use_dr_node
${catkin_LIBRARIES}
)
catkin_make編譯
rqt_reconfigure
使用圖形化工具修改引數,回撥函式結果。
roscore
# 啟動ros節點
rosrun learning_dynamic_reconfigure use_dr_node
# 使用圖形化介面
rosrun rqt_reconfigure rqt_reconfigure
或者使用launch檔案啟動
<launch>
<node name="learning_dr" pkg="learning_dynamic_reconfigure" type="use_dr_node" output="screen"/>
<node name="rqt_reconfigure" pkg="rqt_reconfigure" type="rqt_reconfigure" />
</launch>
功能包使用方法
# 建立工作空間
mkdir ~/catkin_ws/src
cd ~/catkin_ws/src
git clone https://github.com/LadissonLai/learning_dynamic_reconfigure.git
cd ~/catkin_ws
catkin_make
source ./devel/setup.bash
roslaunch learning_dynamic_reconfigure start.launch
完整專案
完整專案檢視github倉庫。