文章目录
- 1.参数服务的概念及应用场景
- 1.1 概念
- 1.2 应用场景
- 2.准备工作
- 3.参数服务的实现
- 3.1 参数数据类型的使用
- 3.2 服务端的实现
- 3.3 客户端的实现
- 3.4 编译及运行
1.参数服务的概念及应用场景
1.1 概念
参数服务是以共享的方式实现不同节点之间数据交互的一种通信模式。保存参数的节点称之为参数服务端,调用参数的节点称之为参数客户端。参数客户端与参数服务端的交互是基于请求响应的,且参数通信的实现本质上对服务通信的进一步封装。
简单说就是可以多个节点访问取数据!
1.2 应用场景
导航实现时,会进行路径规划,路径规划主要包含,全局路径规划和本地路径规划,所谓全局路径规划就是设计一个从出发点到目标点的大致路径;而本地路径规划,则是根据车辆当前路况生成实时的行进路径。
两种路径规划实现,都会使用到车辆的尺寸数据——长度、宽度、高度等。上述场景中,就可以使用参数服务实现,在一个节点下保存车辆尺寸数据,其他节点可以访问该节点并操作这些数据。
简单说全局路径规划不懂得灵活变通。
而本地路径规划就十分灵活,可根据情况适时调整!
2.准备工作
3.参数服务的实现
3.1 参数数据类型的使用
// 创建参数对象
//1.包含头文件;
#include "rclcpp/rclcpp.hpp"
//3.自定义节点类;
class MyParam:public rclcpp::Node{
public:
MyParam():Node("my_param_node_cpp"){
RCLCPP_INFO(this->get_logger(),"参数API的使用");
rclcpp::Parameter p1("car_name","Tiger"); //参数值为字符串类型
rclcpp::Parameter p2("width",0.15); //参数值为浮点类型
rclcpp::Parameter p3("wheels",2); //参数值为整型
// 获取参数值并转换成相应的数据类型
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"car_name = %s", p1.as_string().c_str());
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"width = %.2f", p2.as_double());
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"wheels = %ld", p3.as_int());
// 获取参数的键
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"p1 name = %s", p1.get_name().c_str());
// 获取参数数据类型
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"p1 type_name = %s",
p1.get_type_name().c_str());// 将参数值转换成字符串类型
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"p1 value_to_msg = %s",
p1.value_to_string().c_str());
}
};
int main(int argc, char const *argv[])
{
//2.初始化ROS2客户端;
rclcpp::init(argc,argv);
//4.调用spain汉书,并传入节点对象指针;
rclcpp::spin(std::make_shared<MyParam>());
//5.资源释放
rclcpp::shutdown();
return 0;
}
3.2 服务端的实现
需求: 编写参数服务端, 设置并操作参数。
// 1.包含头文件;
#include "rclcpp/rclcpp.hpp"
// 3.定义节点类;
class MinimalParamServer: public rclcpp::Node{
public:
MinimalParamServer():Node("minimal_param_server",rclcpp::NodeOptions().allow_undeclared_parameters(true)){
}
// 3-1.声明参数;
void declare_param(){
// 声明参数并设置默认值
this->declare_parameter("car_type","Tiger");
this->declare_parameter("height",1.50);
this->declare_parameter("wheels",4);
// 需要设置 rclcpp::NodeOptions().allow_undeclared_parameters(true),否则非法
this->set_parameter(rclcpp::Parameter("undcl_test",100));
}
// 3-2.查询参数
void get_param(){
RCLCPP_INFO(this->get_logger(),"------------------查----------------");
// 获取指定
rclcpp::Parameter car_type = this->get_parameter("car_type");
RCLCPP_INFO(this->get_logger(),"car_type:%s",car_type.as_string().c_str());
RCLCPP_INFO(this->get_logger(),"height:%.2f",this->get_parameter("height").as_double());
RCLCPP_INFO(this->get_logger(),"wheels:%ld",this->get_parameter("wheels").as_int());
RCLCPP_INFO(this->get_logger(),"undcl_test:%ld",this->get_parameter("undcl_test").as_int());
// 判断包含
RCLCPP_INFO(this->get_logger(),"包含car_type? %d",this->has_parameter("car_type"));
RCLCPP_INFO(this->get_logger(),"包含car_typesxxxx? %d",this->has_parameter("car_typexxxx"));
// 获取所有
auto params = this->get_parameters({"car_type","height","wheels"});
for (auto ¶m : params)
{
RCLCPP_INFO(this->get_logger(),"name = %s, value = %s",param.get_name().c_str(), param.value_to_string().c_str());
}
}
// 3-3.修改参数
void update_param(){
RCLCPP_INFO(this->get_logger(),"------------------改----------------");
this->set_parameter(rclcpp::Parameter("height",1.75));
RCLCPP_INFO(this->get_logger(),"height:%.2f",this->get_parameter("height").as_double());
}
// 3-4.删除参数
void del_param(){
RCLCPP_INFO(this->get_logger(),"------------------删----------------");
// this->undeclare_parameter("car_type");
// RCLCPP_INFO(this->get_logger(),"删除操作后, car_type 还存在马? %d",this->has_parameter("car_type"));
RCLCPP_INFO(this->get_logger(),"删除操作前, undcl_test 存在马? %d",this->has_parameter("undcl_test"));
this->undeclare_parameter("undcl_test");
RCLCPP_INFO(this->get_logger(),"删除操作前, undcl_test 存在马? %d",this->has_parameter("undcl_test"));
}
};
int main(int argc, char ** argv){
// 2.初始化 ROS2 客户端;
rclcpp::init(argc,argv);
// 4.创建节点对象指针, 调用参数操作函数, 并传递给 spin 函数;
auto paramServer= std::make_shared<MinimalParamServer>();
paramServer->declare_param();
paramServer->get_param();
paramServer->update_param();
paramServer->del_param();
rclcpp::spin(paramServer);
// 5.释放资源。
rclcpp::shutdown();
return 0;
}
3.3 客户端的实现
需求: 编写参数客户端, 获取或修改服务端参数。
// 1.包含头文件;
#include "rclcpp/rclcpp.hpp"
using namespace std::chrono_literals;
// 3.定义节点类;
class MinimalParamClient: public rclcpp::Node {
public:
MinimalParamClient():Node("paramDemoClient_node"){
paramClient =
std::make_shared<rclcpp::SyncParametersClient>(this,"minimal_param_server");
}
bool connect_server(){
// 等待服务连接
while (!paramClient->wait_for_service(1s))
{
if (!rclcpp::ok())
{
return false;
}
RCLCPP_INFO(this->get_logger(),"服务未连接");
}
return true;
}
// 3-1.查询参数;
void get_param(){
RCLCPP_INFO(this->get_logger(),"-----------参数客户端查询参数-----------");
double height = paramClient->get_parameter<double>("height");
RCLCPP_INFO(this->get_logger(),"height = %.2f", height);
RCLCPP_INFO(this->get_logger(),"car_type 存在吗? %d",
paramClient->has_parameter("car_type"));
auto params = paramClient->get_parameters({"car_type","height","wheels"});
for (auto ¶m : params)
{
RCLCPP_INFO(this->get_logger(),"%s = %s",
param.get_name().c_str(),param.value_to_string().c_str());
}
}
// 3-2.修改参数;
void update_param(){
RCLCPP_INFO(this->get_logger(),"-----------参数客户端修改参数-----------");
paramClient->set_parameters({rclcpp::Parameter("car_type","Mouse"),
rclcpp::Parameter("height",2.0),
//这是服务端不存在的参数, 只有服务端设置了rclcpp::NodeOptions().allow_undeclared_parameters(true)时,
// 这个参数才会被成功设置。
rclcpp::Parameter("width",0.15),
rclcpp::Parameter("wheels",6)});
}
private:
rclcpp::SyncParametersClient::SharedPtr paramClient;
};
int main(int argc, char const *argv[]){
// 2.初始化 ROS2 客户端;
rclcpp::init(argc,argv);
// 4.创建节点对象指针, 调用参数操作函数;
auto paramClient = std::make_shared<MinimalParamClient>();
bool flag = paramClient->connect_server();
if(!flag){
return 0;
}
paramClient->get_param();
paramClient->update_param();
paramClient->get_param();
// 5.释放资源。
rclcpp::shutdown();
return 0;
}
3.4 编译及运行
修改CMakeLists
然后colcon build
然后运行