什么是参数服务器
与之前两种通信的区别
- 之前提到的话题通信、服务通信,是 ROS 中程序之间的通信方式,通俗讲就是两种交流方式。而参数服务器是用于存储交流过程中提到的某一个物品(对象)、或者物品对应的一个属性(对象的属性)。
- 故,前两者为对通信的管理方式,后者为对一些元素(键值对)的管理方式。
- 前两者 Master 主要在第一次通信双方的连接上起作用,但参数服务器会将 Master 作为参数容器使用,参数设置者将参数存储于 Master 中供其他接受节点使用,即其他节点从 Master 上获取参数键值对。
需求
- 实现参数的添加与修改、参数的获取与查询、参数的删除
- 采用 ros::NodeHandle 和 ros::param 两种方式实现
参数服务器之添加与修改
- 主要采用如下两种方式:
- ros::NodeHandle::setParam(新增键名,新增/修改键值)
- ros::param::set(新增键名,新增/修改键值)
- 两种方法中通过传入 “键” 和 “值” 两个信息生成一个键值对,即一个参数
- 只能修改键值,不能修改键名,键名只能删除再重新生成
修改CMakeLists.txt文件
add_executable(param_set_node src/param_set.cpp)
target_link_libraries(param_set_node
${catkin_LIBRARIES}
)
参数新增与修改的具体代码
#include "ros/ros.h"
int main(int argc, char *argv[])
{
setlocale(LC_ALL, "");
ros::init(argc, argv, "param_set_node");
ros::NodeHandle nh;
nh.setParam("type_nh", "robot1");
nh.setParam("radius_nh", 0.15);
ros::param::set("type_ros", "robot2");
ros::param::set("radius_ros", 0.15);
nh.setParam("radius_nh", 0.2);
ros::param::set("radius_ros", 0.8);
return 0;
}
参数服务器之获取与查询
- 主要采用以下三种方式:
- ros::NodeHandle::param(目标键名, 查询键值结果) :返回键对应值的类型,如果没有则为默认
- ros::NodeHandle::getParam(目标键名, 查询键值结果) :返回值为 bool 类型,若为true,则结果会存入第二参数变量中,否则默认
- ros::param::get(目标键名, 查询键值结果):返回值为 bool 类型,若为true,则结果会存入第二参数变量中,否则默认
- 还有其他一些查询方式:
- ros::NodeHandle::getParamCached(目标键名, 查询键值结果):ros::NodeHandle::getParam() 的优化,提高了变量获取的效率,会先从cache中查找
- ros::NodeHandle::getParamNames(键名集合):获取当前参数服务器中的全部键名,存入键名集合中
- ros::NodeHandle::hasParam(目标键名):返回值为 bool 类型,检查是目标键名是否存在
- ros::NodeHandle::SearechParam(目标键名,查询结果键名):如果目标键名存在,则返回“/ + 目标键名”存入查询结果键名;否则,结果键名为空
- ros::param::getParamNames(键名集合):获取当前参数服务器中的全部键名,存入键名集合中
- ros::param::search(目标键名, 查询结果键名):如果目标键名存在,则返回“/ + 目标键名”存入查询结果键名;否则,结果键名为空
- ros::NodeHandle 与 ros::param 两种方法虽然形式上不同,但实现现象相差不大
修改CMakeLists.txt文件
add_executable(param_get_node src/param_get.cpp)
target_link_libraries(param_get_node
${catkin_LIBRARIES}
)
参数获取与查询的具体代码
#include "ros/ros.h"
int main(int argc, char *argv[])
{
setlocale(LC_ALL, "");
ros::init(argc, argv, "param_get_node");
ros::NodeHandle nh;
double radius = nh.param("radius", 0.5);
ROS_INFO("radius = %.2f", radius);
double radius2 = 0.0;
bool get_result2 = nh.getParam("radius", radius2);
if (get_result2)
{
ROS_INFO("获取的半径是:%.2f", radius2);
}
else
{
ROS_WARN("被查询变量不存在!");
}
float radius3 = 0.0;
bool get_result3 = nh.getParamCached("radius", radius3);
if (get_result3)
{
ROS_INFO("获取的半径是:%.2f", radius3);
}
else
{
ROS_WARN("被查询变量不存在!");
}
std::vector<std::string> names;
nh.getParamNames(names);
for (auto &&name : names)
{
ROS_INFO("遍历到的元素: %s", name.c_str());
}
bool get_result51 = nh.hasParam("radius_ros");
bool get_result52 = nh.hasParam("radius123");
ROS_INFO("radius_ros 存在? %d", get_result51);
ROS_INFO("radius123 存在? %d", get_result52);
std::string key1;
std::string key2;
nh.searchParam("radius_ros", key1);
ROS_INFO("搜索结果:%s", key1.c_str());
nh.searchParam("radius123", key2);
ROS_INFO("搜索结果:%s", key2.c_str());
double radius_ros_param = ros::param::param("radius_ros", 100.5);
ROS_INFO("radius_ros_param = %.2f", radius_ros_param);
std::vector<std::string> names_param;
ros::param::getParamNames(names_param);
int i = 1;
for (auto &&name : names_param)
{
ROS_INFO("键名 %d : %s", i, name.c_str());
i++;
}
std::string key;
ros::param::search("param_int", key);
ROS_INFO("搜索键 param_int :%s", key.c_str());
ros::param::search("radius_ros", key);
ROS_INFO("搜索键 radius_ros :%s", key.c_str());
double radius_get = 0.0;
bool flag_ros_get = ros::param::get("radius_ros", radius_get);
if (flag_ros_get)
{
ROS_INFO("radius_ros = %.2f", radius_get);
}
else
{
ROS_INFO("不存在!");
}
return 0;
}
参数服务器之删除
- 主要如下两种方法:
- ros::NodeHandle::deleteParam(目标键名):返回值为 bool 类型
- ros::param::del(目标键名) :返回值为 bool 类型
修改CMakeLists.txt文件
add_executable(param_del_node src/param_del.cpp)
target_link_libraries(param_del_node
${catkin_LIBRARIES}
)
参数删除的具体代码
#include <ros/ros.h>
int main(int argc, char *argv[])
{
setlocale(LC_ALL, "");
ros::init(argc, argv, "param_del");
ros::NodeHandle nh;
bool flag_del_nh = nh.deleteParam("radius_ros");
if (flag_del_nh)
{
ROS_INFO("删除成功!");
}
else
{
ROS_INFO("删除失败!");
}
bool flag_ros_ros = ros::param::del("radius_ros");
if (flag_ros_ros)
{
ROS_INFO("删除成功!");
}
else
{
ROS_INFO("删除失败!");
}
return 0;
}