参数服务器是什么呢,就相当于我们有一个参数容器,然后我们要从中获取一些数据,或者对数据进行增删查改的操作。比如我们要对机器人进行路径规划,那有些地方是限制大小才能允许通过的,这个时候我们就需要知道机器人自身的尺寸吧,它自己大了就无法通过,那获取这个数据我们就可以用参数服务器实现,那对参数服务器参数的增删改查操作改如何用c++来实现呢,就是我们下面的内容。
1.建立功能包
别忘了添加依赖
2.参数服务器新增参数
创建一个实现此功能的cpp 编辑cpp
#include"ros/ros.h"
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
ros::init(argc,argv,"set_change_param");
ros::NodeHandle nh;
nh.setParam("nh_int",5);
nh.setParam("nh_double",0.1);
nh.setParam("nh_bool",true);
nh.setParam("nh_string","ss");
std::vector<std::string> vec;
vec.push_back("张三");
vec.push_back("李四");
vec.push_back("王五");
nh.setParam("nh_vec",vec);
std::map<std::string,std::int32_t>mp;
mp["C语言"]=1;
mp["C++"]=2;
mp["java"]=3;
nh.setParam("nh_map",mp);
return 0;
}
编辑Cmakelist.txt 为了避免难记,就把可执行文件名同cpp文件名就行 Ctrl + Shift + B编译 没问题 开终端来运行一下
3.参数服务器修改参数
修改的话也用setParam,只是说,把相同名的参数的值改变了,另一种实现用ros::param::set()也可以 代码如下
#include"ros/ros.h"
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
ros::init(argc,argv,"set_change_param");
ros::NodeHandle nh;
nh.setParam("nh_int",5);
nh.setParam("nh_double",0.1);
nh.setParam("nh_bool",true);
nh.setParam("nh_string","ss");
std::vector<std::string> vec;
vec.push_back("张三");
vec.push_back("李四");
vec.push_back("王五");
nh.setParam("nh_vec",vec);
std::map<std::string,std::int32_t>mp;
mp["C语言"]=1;
mp["C++"]=2;
mp["java"]=3;
nh.setParam("nh_map",mp);
nh.setParam("nh_int",10);
ros::param::set("nh_double",0.5);
vec.erase(vec.begin());
ros::param::set("nh_vec",vec);
mp["C语言"]=2;
ros::param::set ("nh_map",mp);
return 0;
}
修改后的终端效果 double和map[“C语言”]的值确实改变了
4.参数服务器获取参数
照样有ros::NodeHandle和 ros::param 两种实现
ros::NodeHandle
param(键,默认值)
存在,返回对应结果,否则返回默认值
getParam(键,存储结果的变量)
存在,返回 true,且将值赋值给参数2
若果键不存在,那么返回值为 false,且不为参数2赋值
getParamCached键,存储结果的变量)--提高变量获取效率
存在,返回 true,且将值赋值给参数2
若果键不存在,那么返回值为 false,且不为参数2赋值
getParamNames(std::vector<std::string>)
获取所有的键,并存储在参数 vector 中
hasParam(键)
是否包含某个键,存在返回 true,否则返回 false
searchParam(参数1,参数2)
搜索键,参数1是被搜索的键,参数2存储搜索结果的变量
ros::param ----- 与 NodeHandle 类似
param函数,nh_int之前存在,值为10,nh_int2不存在 结果:
getParam 函数,键存在就赋值给参数2,不存在就不赋值,输出参数2就会输出为空
int nh_int_value;
double nh_double_value;
bool nh_bool_value;
std::string nh_string_value;
std::vector<std::string> vec;
std::map<std::string, std::int32_t>mp;
nh.getParam("nh_int",nh_int_value);
nh.getParam("nh_double",nh_double_value);
nh.getParam("nh_bool",nh_bool_value);
nh.getParam("nh_string",nh_string_value);
nh.getParam("nh_vec",vec);
nh.getParam("nh_map",mp);
ROS_INFO("getParam获取的结果:%d,%.2f,%s,%d",
nh_int_value,
nh_double_value,
nh_string_value.c_str(),
nh_bool_value
);
for (auto &k : vec)
{
ROS_INFO("vector 元素:%s",k.c_str());
}
for (auto &f : mp)
{
ROS_INFO("map 元素:%s = %d",f.first.c_str(), f.second);
}
结果 getParamCached 会更快一些而已,要求高性能就可以用这个
nh.getParamCached("nh_int",nh_int_value);
ROS_INFO("通过缓存获取数据:%d",nh_int_value);
getParamNames()函数,得到所有的键(参数名字)
std::vector<std::string> names;
nh.getParamNames(names);
for (auto &name : names)
{
ROS_INFO("名称解析name = %s",name.c_str());
}
结果;
hasParam函数,有无某个参数名字
bool flag1=nh.hasParam("nh_int");
bool flag2=nh.hasParam("nh_int2");
ROS_INFO("存在 nh_int 吗? %d",flag1);
ROS_INFO("存在 nh_int2 吗? %d",flag2);
结果
searchParam函数,不存在的键,其参数不赋值
std::string key1;
nh.searchParam("nh_int",key1);
ROS_INFO("搜索键:%s",key1.c_str());
std::string key2;
nh.searchParam("nh_int2",key2);
ROS_INFO("搜索键:%s",key2.c_str());
总代码:
#include "ros/ros.h"
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
ros::init(argc,argv,"search_param");
ros::NodeHandle nh;
int res1 = nh.param("nh_int",100);
int res2 = nh.param("nh_int2",100);
ROS_INFO("获取整数结果:%d,%d",res1,res2);
int nh_int_value;
double nh_double_value;
bool nh_bool_value;
std::string nh_string_value;
std::vector<std::string> vec;
std::map<std::string, std::int32_t>mp;
nh.getParam("nh_int",nh_int_value);
nh.getParam("nh_double",nh_double_value);
nh.getParam("nh_bool",nh_bool_value);
nh.getParam("nh_string",nh_string_value);
nh.getParam("nh_vec",vec);
nh.getParam("nh_map",mp);
ROS_INFO("getParam获取的结果:%d,%.2f,%s,%d",
nh_int_value,
nh_double_value,
nh_string_value.c_str(),
nh_bool_value
);
for (auto &k : vec)
{
ROS_INFO("vector 元素:%s",k.c_str());
}
for (auto &f : mp)
{
ROS_INFO("map 元素:%s = %d",f.first.c_str(), f.second);
}
nh.getParamCached("nh_int",nh_int_value);
ROS_INFO("通过缓存获取数据:%d",nh_int_value);
std::vector<std::string> names;
nh.getParamNames(names);
for (auto &name : names)
{
ROS_INFO("名称解析name = %s",name.c_str());
}
bool flag1=nh.hasParam("nh_int");
bool flag2=nh.hasParam("nh_int2");
ROS_INFO("存在 nh_int 吗? %d",flag1);
ROS_INFO("存在 nh_int2 吗? %d",flag2);
std::string key1;
nh.searchParam("nh_int",key1);
ROS_INFO("搜索键:%s",key1.c_str());
std::string key2;
nh.searchParam("nh_int2",key2);
ROS_INFO("搜索键:%s",key2.c_str());
return 0;
}
ros::param实现的话也类似
5.参数服务器删除参数
ros::NodeHandle
deleteParam("键")
根据键删除参数,删除成功,返回 true,否则(参数不存在),返回 false
ros::param
del("键")
根据键删除参数,删除成功,返回 true,否则(参数不存在),返回 false
代码:
#include "ros/ros.h"
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
ros::init(argc,argv,"delet_param");
ros::NodeHandle nh;
bool flag1 = nh.deleteParam("nh_int");
if(flag1){
ROS_INFO("第一次删除nh_int成功");
}
else{
ROS_INFO("第一次删除nh_int失败");
}
bool flag2 = ros::param::del("nh_int");
if(flag2){
ROS_INFO("第二次删除nh_int成功");
}
else{
ROS_INFO("第二次删除nh_int失败");
}
return 0;
}
结果;
|