0.前言
在 C++ 中实现参数服务器数据的增删改查,可以通过两套 API 实现:
-
ros::NodeHandle
-
ros::param
在上述两个API中,内置了增删改查的操作函数。
在实现具体的功能前,要做一些准备工作。
基于前面已经有较多的代码,于是决定新建一个工作空间,新建的方法不再赘述,不会的话,请转至 3rd. VSCode下开发ROS的基本流程(C++/Python)
一、 增/改参数
1.1 参数的新增
需求:设置机器人的共享参数,类型和半径(0.15)
实现:
ros::NodeHandle
setParam()
ros::param
set()
1.1.1 新建文件
#include<ros/ros.h>
/*
需要实现参数的新增和修改
需求:设置机器人的共享参数,类型和半径(0.15)
再修改半径为0.2
实现:
ros::NodeHandle
setParam()
ros::param
set()
*/
int main(int argc, char *argv[])
{
//初始化ros节点
ros::init(argc,argv,"set_param_c");
//创建节点句柄
ros::NodeHandle nh;
//实现参数的增加
//方案1:
nh.setParam("TypeRobot","xiaohuang");
nh.setParam("radius",0.15);
//方案2:
ros::param::set("typerobot","xiaobai");
ros::param::set("radius_",0.15);
//实现参数的改
return 0;
}
1.1.2 配置
在CMakeList.txt中,进行配置:
1.1.3 编译
编译:Ctrl + Shift + B
1.1.4 测试
使用命令查看 rosparam list
查看参数的值命令:rosparam get 参数名
1.2 参数的修改
ros::NodeHandle
setParam()
ros::param
set()
依然使用这些个命令,对参数的值进行覆盖。
二、参数的查
2.1新建文件
#include<ros/ros.h>
/*
需要实现参数的查询
参数服务器操作之查询_C++实现:
在 roscpp 中提供了两套 API 实现参数操作
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 类似
*/
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
//初始化ros节点
ros::init(argc,argv,"get_param_c");
//创建节点句柄
ros::NodeHandle nh;
//------------------ros::NodeHandle--------------------
//1. param(键,默认值) 存在,返回对应结果,否则返回默认值
double radius = nh.param("radius",0.5);
ROS_INFO("radius = %.2f",radius);
return 0;
}
2.2 配置
2.3 测试
2.4 完整操作(六种方法)
#include<ros/ros.h>
/*
需要实现参数的查询
参数服务器操作之查询_C++实现:
在 roscpp 中提供了两套 API 实现参数操作
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 类似
*/
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
//初始化ros节点
ros::init(argc,argv,"get_param_c");
//创建节点句柄
ros::NodeHandle nh;
//------------------ros::NodeHandle--------------------
//1. param(键,默认值) 存在,返回对应结果,否则返回默认值
double radius = nh.param("radius",0.5);
ROS_INFO("radius = %.2f",radius);
//2.getParam
// getParam(键,存储结果的变量)
// 存在,返回 true,且将值赋值给参数2
// 若果键不存在,那么返回值为 false,且不为参数2赋值
double radius2;
bool result = nh.getParam("radius",radius2);
if(result)
{
ROS_INFO("获取的半径是: %.2f",radius2);
}
else
{
ROS_INFO("被查询的变量不存在");
}
//3.getParamCached键,存储结果的变量)--提高变量获取效率
//从缓存中获取
// 存在,返回 true,且将值赋值给参数2
// 若果键不存在,那么返回值为 false,且不为参数2赋值
double radius3;
bool result3 = nh.getParam("radius",radius2);
if(result3)
{
ROS_INFO("获取的半径是: %.2f",radius2);
}
else
{
ROS_INFO("被查询的变量不存在");
}
// 4.getParamNames(std::vector<std::string>)
// 获取所有的键,并存储在参数 vector 中
std::vector<std::string>names;
nh.getParamNames(names);
for (auto &&name:names)
{
ROS_INFO("遍历到的元素为:%s",name.c_str());
}
//5.hasParam(键)
// 是否包含某个键,存在返回 true,否则返回 false
bool flag1 = nh.hasParam("radius");
bool flag2 = nh.hasParam("radius_no");
ROS_INFO("radius存在吗?%d",flag1);
ROS_INFO("radius_no存在吗?%d",flag2);
// 6. searchParam(参数1,参数2)
// 搜索键,参数1是被搜索的键,参数2存储搜索结果的变量
std::string key;
nh.searchParam("radius",key);
ROS_INFO("搜索结果:%s",key.c_str());
return 0;
}
其中,另一套API,ros::param也对应着类似的函数,如图所示,这里不再赘述:
三、参数的删除
3.1新建文件
#include<ros/ros.h>
/*
需要实现参数的删除
实现:
ros::NodeHandle
deleteParam()
ros::param
del()
*/
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
ros::init(argc,argv,"param_delete");
ros::NodeHandle nh;
//删除:NodleHandle-----------------
bool flag_success = nh.deleteParam("radius");
if(flag_success)
{
ROS_INFO("删除成功");
}
else
{
ROS_INFO("删除失败");
}
//删除:ros:param————————
bool flag_success2 = ros::param::del("radius_");
if(flag_success2)
{
ROS_INFO("删除成功");
}
else
{
ROS_INFO("删除失败");
}
return 0;
}
3.2 配置
3.3编译并测试
编译:Ctrl + Shift + B