ROS2 参数(C++)

实验目的:

        参数相关API函数使用;

        服务端实现对参数的增、查、改、删操作

        客户端连接服务端,并实现对参数的增、查、改、删操作

1、创建工作空间

        请参考:ROS2 话题通信——自定义消息类型(C++)-CSDN博客 

2、创建功能包

        创建服务功能包param_pkg,新建参数API使用节点param_api.cpp

cd text_w/src/
ros2 pkg create param_pkg --build-type ament_cmake --dependencies rclcpp --node-name param_api

3、编写param_api节点并测试

#include "rclcpp/rclcpp.hpp"//1.包含头文件


//自定义类继承Node
class ParamNode: public rclcpp::Node{
    public:
        ParamNode():Node("param_node"){
            RCLCPP_INFO(this->get_logger(),"参数API使用");

            //参数对象创建
            rclcpp::Parameter p1("car_name","tiger"); 
            rclcpp::Parameter p2("height",1.8); 
            rclcpp::Parameter p3("wheels",4); 

            //参数对象解析,解析值
            RCLCPP_INFO(this->get_logger(),"car_name = %s",p1.as_string().c_str());
            RCLCPP_INFO(this->get_logger(),"height = %.2f",p2.as_double());
            RCLCPP_INFO(this->get_logger(),"wheels = %ld",p3.as_int());

            //获取参数键
            RCLCPP_INFO(this->get_logger(),"name = %s",p1.get_name().c_str());//键名字
            RCLCPP_INFO(this->get_logger(),"type = %s",p1.get_type_name().c_str());//键类型
            RCLCPP_INFO(this->get_logger(),"value2string = %s",p2.value_to_string().c_str());//值

        }

};

int main(int argc, char * argv[])                               
{
    //初始化ROS2客户端
    rclcpp::init(argc, argv);     

    //实例化自定义类
    auto node = std::make_shared<ParamNode>();
    
    //释放资源
    rclcpp::shutdown();                             
    
    return 0;
}

        编译测试一下

cd ..
colcon build --packages-select param_pkg
source install/setup.bash 
ros2 run param_pkg param_api 

         测试成功

4、参数服务端和参数客户端实现

      新建param_server.cpp和param_client.cpp文件,并修改CMakeLists.txt文件

cmake_minimum_required(VERSION 3.8)
project(param_pkg)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)

add_executable(param_api src/param_api.cpp)

add_executable(param_server src/param_server.cpp)

add_executable(param_client src/param_client.cpp)

target_include_directories(param_server PUBLIC
  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
  $<INSTALL_INTERFACE:include>)
target_compile_features(param_server PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17

ament_target_dependencies(
  param_api
  "rclcpp"
)


ament_target_dependencies(
  param_server
  "rclcpp"
)


ament_target_dependencies(
  param_client
  "rclcpp"
)

install(TARGETS param_api
  DESTINATION lib/${PROJECT_NAME})

install(TARGETS param_server
  DESTINATION lib/${PROJECT_NAME})

install(TARGETS param_client
  DESTINATION lib/${PROJECT_NAME})

if(BUILD_TESTING)
  find_package(ament_lint_auto REQUIRED)
  # the following line skips the linter which checks for copyrights
  # comment the line when a copyright and license is added to all source files
  set(ament_cmake_copyright_FOUND TRUE)
  # the following line skips cpplint (only works in a git repo)
  # comment the line when this package is in a git repo and when
  # a copyright and license is added to all source files
  set(ament_cmake_cpplint_FOUND TRUE)
  ament_lint_auto_find_test_dependencies()
endif()

ament_package()

        编写参数服务端

#include "rclcpp/rclcpp.hpp"//1.包含头文件


//自定义类继承Node
class ParamServer: public rclcpp::Node{
    public:
        //如果允许删除参数,那么需要NodeOptions声明
        ParamServer():Node("param_server_node",rclcpp::NodeOptions().allow_undeclared_parameters(true)){
            RCLCPP_INFO(this->get_logger(),"参数服务端");

        }

        //增
        void declare_param(){
            RCLCPP_INFO(this->get_logger(),"----------------增----------------");
            this->declare_parameter("car_name","tiger");
            this->declare_parameter("width",1.55);
            this->declare_parameter("wheels",5);
        }

        //查
        void get_param(){
            RCLCPP_INFO(this->get_logger(),"----------------查----------------");

            //获取指定参数
            auto car = this->get_parameter("car_name");
            RCLCPP_INFO(this->get_logger(),"key = %s , value = %s",car.get_name().c_str(),car.as_string().c_str());

            //获取一些参数
            auto params = this->get_parameters({"car_name","width","wheels"});

            for(auto &&param : params)
            {
                RCLCPP_INFO(this->get_logger(),"(%s = %s)",param.get_name().c_str(),param.value_to_string().c_str());
            }

            //判断是否包含
            RCLCPP_INFO(this->get_logger(),"是否包含car_name:%d",this->has_parameter("car_name"));
            RCLCPP_INFO(this->get_logger(),"是否包含height:%d",this->has_parameter("height"));

        }

        //改
        void update_param(){
            RCLCPP_INFO(this->get_logger(),"----------------改----------------");
            this->set_parameter(rclcpp::Parameter("width",1.65));
            RCLCPP_INFO(this->get_logger(),"width = %.2f",this->get_parameter("width").as_double());
        }

        //删
        void de_param(){
            RCLCPP_INFO(this->get_logger(),"----------------删----------------");
            //this->undeclare_parameter("car_name");//不能删除声明的参数

            RCLCPP_INFO(this->get_logger(),"删除后是否包含car_name:%d",this->has_parameter("car_name"));
        }

};

int main(int argc, char * argv[])                               
{
    //初始化ROS2客户端
    rclcpp::init(argc, argv);     

    //实例化自定义类
    auto node = std::make_shared<ParamServer>();
    
    node->declare_param();
    node->get_param();
    node->update_param();
    node->de_param();

    rclcpp::spin(node);

    //释放资源
    rclcpp::shutdown();    

    return 0;
}

        编写参数客户端

#include "rclcpp/rclcpp.hpp"//1.包含头文件

using namespace std::chrono_literals;

//自定义类继承Node
class ParamClient: public rclcpp::Node{
    public:
        ParamClient():Node("param_client_node"){
            RCLCPP_INFO(this->get_logger(),"参数客户端");

            param_client_ = std::make_shared<rclcpp::SyncParametersClient>(this,"param_server_node");//(当前对象依赖的节点,参数服务端节点名称)

        }

        //连接服务器
        bool connect_server(){
            while(!param_client_->wait_for_service(1s))//循环一秒为超时间连接服务器,直到连接到服务器才退出循环
            {
              //对ctrl+c 作出处理
              if(!rclcpp::ok())
              {
                RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "强行终止客户端!");
                return false;
              }
              RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "服务器连接中......");
            }
            return true;
        }

        //查询参数
        void get_param(){
            RCLCPP_INFO(this->get_logger(),"----------------查----------------");
            
            //获取指定参数
            std::string car_name = param_client_->get_parameter<std::string>("car_name");
            double width = param_client_->get_parameter<double>("width");

            RCLCPP_INFO(this->get_logger(),"car_name = %s",car_name.c_str());
            RCLCPP_INFO(this->get_logger(),"width = %.2f",width);
         
            //获取一些参数
            auto params = param_client_->get_parameters({"car_name","width","wheels"});

            for(auto &&param : params)
            {
                RCLCPP_INFO(this->get_logger(),"(%s = %s)",param.get_name().c_str(),param.value_to_string().c_str());
            }

            //判断是否包含
            RCLCPP_INFO(this->get_logger(),"是否包含car_name:%d",param_client_->has_parameter("car_name"));
            RCLCPP_INFO(this->get_logger(),"是否包含height:%d",param_client_->has_parameter("height"));
            
        }

        //修改参数
        void update_param(){
            RCLCPP_INFO(this->get_logger(),"----------------改----------------");
            param_client_->set_parameters({
                rclcpp::Parameter("car_name","pig"),
                rclcpp::Parameter("width",3.0)   
            });
        }

    private:
        rclcpp::SyncParametersClient::SharedPtr param_client_;

};

int main(int argc, char * argv[])                               
{
    //初始化ROS2客户端
    rclcpp::init(argc, argv);     

    //实例化自定义类
    auto node = std::make_shared<ParamClient>();
    
    //调用客户端对象连接服务器功能
    bool flag = node->connect_server();

    //判断是否连接上服务器
    if(!flag)
    {
        RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "服务器连接失败!");
        return 0;
    }

    node->get_param();
    node->update_param();
    node->get_param();
    
    //释放资源
    rclcpp::shutdown();    
    
    return 0;
}

5、测试

         分别开两个终端编译并测试一下

colcon build --packages-select param_pkg
source install/setup.bash 
ros2 run param_pkg param_server 


source install/setup.bash 
ros2 run param_pkg param_client

        测试成功。 

  • 3
    点赞
  • 10
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值