🔥码云GVP开源项目 12k star Uniapp+ElementUI 功能强大 支持多语言、二开方便! 广告
# 6.5 param in roscpp ## 6.5.1 Parameter Server 严格来说,param并不能称作一种通信方式,因为它往往只是用来存储一些静态的设置,而不是动态变化的。所以关于param的操作非常轻巧,非常简单。 关于param的API,roscpp为我们提供了两套,一套是放在`ros::param`namespace下,另一套是在`ros::NodeHandle`下,这两套API的操作完全一样,用哪一个取决于你的习惯。 ## 6.5.2 param_demo 我们来看看在C++中如何进行param_demo的操作,`param_demo/param.cpp`文件,内容包括: ```cpp #include<ros/ros.h> int main(int argc, char **argv){ ros::init(argc, argv, "param_demo"); ros::NodeHandle nh; int parameter1, parameter2, parameter3, parameter4, parameter5; //Get Param的三种方法 //① ros::param::get()获取参数“param1”的value,写入到parameter1上 bool ifget1 = ros::param::get("param1", parameter1); //② ros::NodeHandle::getParam()获取参数,与①作用相同 bool ifget2 = nh.getParam("param2",parameter2); //③ ros::NodeHandle::param()类似于①和② //但如果get不到指定的param,它可以给param指定一个默认值(如33333) nh.param("param3", parameter3, 33333); if(ifget1) //param是否取得 ... //Set Param //① ros::param::set()设置参数 parameter4 = 4; ros::param::set("param4", parameter4); //② ros::NodeHandle::setParam()设置参数 parameter5 = 5; nh.setParam("param5",parameter5); //Check Param //① ros::NodeHandle::hasParam() bool ifparam5 = nh.hasParam("param5"); //② ros::param::has() bool ifparam6 = ros::param::has("param6"); //Delete Param //① ros::NodeHandle::deleteParam() bool ifdeleted5 = nh.deleteParam("param5"); //② ros::param::del() bool ifdeleted6 = ros::param::del("param6"); ... } ``` 以上是roscpp中对param进行增删改查所有操作的方法,非常直观。 ## 6.5.3 param_demo中的launch文件 实际项目中我们对参数进行设置,尤其是添加参数,一般都不是在程序中,而是在launch文件中。因为launch文件可以方便的修改参数,而写成代码之后,修改参数必须重新编译。 因此我们会在launch文件中将param都定义好,比如这个demo正确的打开方式应该是`roslaunch param_demo param_demo_cpp.launch` `param_demo/launch/param_demo_cpp.launch`内容为: ```xml <launch> <!--param参数配置--> <param name="param1" value="1" /> <param name="param2" value="2" /> <!--rosparam参数配置--> <rosparam> param3: 3 param4: 4 param5: 5 </rosparam> <!--以上写法将参数转成YAML文件加载,注意param前面必须为空格,不能用Tab,否则YAML解析错误--> <!--rosparam file="$(find robot_sim_demo)/config/xbot2_control.yaml" command="load" /--> <node pkg="param_demo" type="param_demo" name="param_demo" output="screen" /> </launch> ``` 通过<param>和<rosparam>两个标签我们设置好了5个param,从而在之前的代码中进行增删改查的操作。 ## 6.5.3 命名空间对param的影响 在实际的项目中,实例化句柄时,经常会看到两种不同的写法 ros::NodeHandle n; ros::NodeHandle nh("~");` 这两种写法有什么不同呢?以本教学报的name_demo为例。在本节launch文件夹的demo.launch定义两个参数,一个全局serial 他的数值是5,一个是局部的serial,他的数值是10. ```xml <launch> <!--全局参数serial--> <param name="serial" value="5" /> <node name="name_demo" pkg="name_demo" type="name_demo" output="screen"> <!--局部参数serial--> <param name="serial" value="10" /> </node> </launch> ``` 在name_demo.cpp中,我们分别尝试了,利用全局命名空间句柄提取全局的param和局部的param,以及在局部命名空间下的句柄提取全局的param和局部的param,详细的代码如下: ```cpp #include <ros/ros.h> int main(int argc, char* argv[]) { int serial_number = -1;//serial_number初始化 ros::init(argc, argv, "name_demo");//node初始化 /*创建命名空间*/ //n 是全局命名空间 ros::NodeHandle n; //nh 是局部命名空间 ros::NodeHandle nh("~"); /*全局命名空间下的Param*/ ROS_INFO("global namespace"); //提取全局命名空间下的参数serial n.getParam("serial", serial_number); ROS_INFO("global_Serial was %d", serial_number); //提取局部命名空间下的参数serial n.getParam("name_demo/serial", serial_number);//在全局命名空间下,要提取局部命名空间下的参数,需要添加node name ROS_INFO("global_to_local_Serial was %d", serial_number); /*局部命名空间下的Param*/ ROS_INFO("local namespace"); //提取局部命名空间下的参数serial nh.getParam("serial", serial_number); ROS_INFO("local_Serial was %d", serial_number); //提取全局命名空间下的参数serial nh.getParam("/serial", serial_number);//在局部命名空间下,要提取全局命名空间下的参数,需要添加“/” ROS_INFO("local_to_global_Serial was %d", serial_number); ros::spin(); return 0; } ``` 最后的结果 ```xml [ INFO] [1525095241.802257811]: global namespace [ INFO] [1525095241.803512501]: global_Serial was 5 [ INFO] [1525095241.804515959]: global_to_local_Serial was 10 [ INFO] [1525095241.804550167]: local namespace [ INFO] [1525095241.805126562]: local_Serial was 10 [ INFO] [1525095241.806137701]: local_to_global_Serial was 5 ```