[ROS2] --- param

1 param介绍

类似C++编程中的全局变量,可以便于在多个程序中共享某些数据,参数是ROS机器人系统中的全局字典,可以运行多个节点中共享数据。

  • 全局字典
    在ROS系统中,参数是以全局字典的形态存在的,什么叫字典?就像真实的字典一样,由名称和数值组成,也叫做键和值,合成键值。或者我们也可以理解为,就像编程中的参数一样,有一个参数名 ,然后跟一个等号,后边就是参数值了,在使用的时候,访问这个参数名即可。

  • 可动态监控
    在ROS2中,参数的特性非常丰富,比如某一个节点共享了一个参数,其他节点都可以访问,如果某一个节点对参数进行了修改,其他节点也有办法立刻知道,从而获取最新的数值。这在参数的高级编程中,大家都可能会用到。

2 param编码示例

这里创建功能包名为,learning05_param

2.1 parameter.cpp

/**
 * @file parameters.cpp
 *
 * @brief A node to declare and get parameters
 *        Here the parameters are the message data for two publisher
 *        It's possible to change them at run time using the commad line
 *        "ros2 param set /set_parameter_node vehicle_speed 100"
 *        "ros2 param set /set_parameter_node vehicle_type car"
 *        or using a launch file
 *
 * @author Antonio Mauro Galiano
 * Contact: https://www.linkedin.com/in/antoniomaurogaliano/
 *
 */

#include <chrono>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "std_msgs/msg/int16.hpp"

using namespace std::chrono_literals;

class MySetParameterClass: public rclcpp::Node
{
private:
  int velocityParam_;
  std::string typeVehicleParam_;
  rclcpp::TimerBase::SharedPtr timer_;
  rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pubString_;
  rclcpp::Publisher<std_msgs::msg::Int16>::SharedPtr pubInt_;
  void TimerCallback();

public:
  MySetParameterClass()
    : Node("set_parameter_node")
  {
    // here are declared the parameters and their default values
    this->declare_parameter<std::string>("vehicle_type", "bike");
    this->declare_parameter<int>("vehicle_speed", 10);
    pubString_ = this->create_publisher<std_msgs::msg::String>("/vehicle_type", 10);
    pubInt_ = this->create_publisher<std_msgs::msg::Int16>("/vehicle_speed", 10);
    timer_ = this->create_wall_timer(
      1000ms, std::bind(&MySetParameterClass::TimerCallback, this));
  }
};


void MySetParameterClass::TimerCallback()
{
  // here the params get their value from outside
  // such as a set command or a launch file
  this->get_parameter("vehicle_type", typeVehicleParam_);
  this->get_parameter("vehicle_speed", velocityParam_);
  std_msgs::msg::String messageString;
  messageString.data=typeVehicleParam_;
  std_msgs::msg::Int16 messageInt;
  messageInt.data=velocityParam_;
  RCLCPP_INFO(this->get_logger(), "Publishing two messages -> vehicle type %s\tVehicle speed %d",
    typeVehicleParam_.c_str(), velocityParam_);
  pubInt_->publish(messageInt);
  pubString_->publish(messageString);
}


int main(int argc, char** argv)
{
  rclcpp::init(argc, argv);
  auto node = std::make_shared<MySetParameterClass>();
  rclcpp::spin(node);
  rclcpp::shutdown();
  return 0;
}

2.2 CMakeLists.txt

cmake_minimum_required(VERSION 3.5)
project(learning05_param)

# Default to C99
if(NOT CMAKE_C_STANDARD)
  set(CMAKE_C_STANDARD 99)
endif()

# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
  set(CMAKE_CXX_STANDARD 14)
endif()

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)
find_package(std_msgs REQUIRED)

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

add_executable(parameters src/parameters.cpp)
ament_target_dependencies(parameters rclcpp std_msgs)

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

ament_package()

2.3 package.xml

<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
  <name>learning05_param</name>
  <version>0.0.0</version>
  <description>Example node to handle parameters</description>
  <maintainer email="[email protected]">Antonio Mauro Galiano</maintainer>
  <license>TODO: License declaration</license>

  <buildtool_depend>ament_cmake</buildtool_depend>

  <depend>rclcpp</depend>

  <test_depend>ament_lint_auto</test_depend>
  <test_depend>ament_lint_common</test_depend>

  <export>
    <build_type>ament_cmake</build_type>
  </export>
</package>

3 编译运行

# 编译
colcon build

# source环境变量
source install/setup.sh

# 运行parameters节点
ros2 run learning05_param parameters

可以看到
在这里插入图片描述
再开一个终端,
在这里插入图片描述
这里set了vehicle_speed值为12,可以看到运行的程序中vehicle_speed的值从10 变为了12
在这里插入图片描述

4 param常用指令

查看列表参数
ros2 param list

ros2 param list
/set_parameter_node:
use_sim_time
vehicle_speed
vehicle_type


查看描述
ros2 param describe /set_parameter_node use_sim_time

ros2 param describe /set_parameter_node use_sim_time
Parameter name: use_sim_time
Type: boolean
Constraints:


获取参数值
ros2 param get /set_parameter_node use_sim_time
Boolean value is: False

设置参数值
ros2 param set /set_parameter_node use_sim_time true
Set parameter successful


将一个节点所有的param写在一个yaml文件中
ros2 param dump /set_parameter_node
Saving to:  ./set_parameter_node.yaml

修改上面的yaml文件,通过下面指令直接生效
ros2 param load /set_parameter_node set_parameter_node.yaml 
Set parameter use_sim_time successful
Set parameter vehicle_speed successful
Set parameter vehicle_type successful

猜你喜欢

转载自blog.csdn.net/weixin_42445727/article/details/134887887