ros2 parameter编程
1 前言和资料
在ROS2高效学习第二章 – ros2常用命令和相关概念学习,熟练玩起来小乌龟样例这篇博客里,我们讲解了 ros2 parameter 的基本概念,介绍了命令行获取和设置节点参数的方法,本文我们讲解 ros2 parameter 编程,并使用 cpp 和 python 两种语言,实现 parameter 编程样例。
本文参考资料如下:
(1)ROS2高效学习第二章 – ros2常用命令和相关概念学习,熟练玩起来小乌龟样例 第2.6节
(2)Using-Parameters-In-A-Class-CPP
(3)Using-Parameters-In-A-Class-Python
(4)Monitoring-For-Parameter-Changes-CPP
2 正文
2.1 parameters_cpp
(1)功能介绍:在 parameters_cpp 中,我们将实现两个节点。
第一个 param_test 节点,我们将测试 ros2 parameter 编程的两种参数设置方式,分别是 launch 文件设置和 API 接口设置。
第二个 param_monitor 节点,我们将编码实现参数监控,既监控本节点参数,也监控其他节点参数的改动。在实际开发中,监控参数改动有比较多的应用。
(2)创建 parameters_cpp 软件包和文件
cd ~/colcon_ws/src
ros2 pkg create --build-type ament_cmake --license Apache-2.0 parameters_cpp --dependencies rclcpp
cd parameters_cpp
mkdir launch
touch launch/param_test_launch.py launch/param_monitor_launch.py
touch src/param_test.cpp src/param_monitor.cpp
(3)编写 param_test.cpp
#include <chrono>
#include <functional>
#include <string>
#include "rclcpp/rclcpp.hpp"
class MiniParam : public rclcpp::Node {
public:
MiniParam() : Node("test_param_cpp") {
// set param description
auto param_desc = rcl_interfaces::msg::ParameterDescriptor{};
param_desc.description = "This parameter is mine!";
// "set in cpp !!" will be cover by launch file: "set in launch !!"
this->declare_parameter("demo_param", "set in cpp !!", param_desc);
timer_ = this->create_wall_timer(std::chrono::seconds(1), std::bind(&MiniParam::timer_cb, this));
}
void timer_cb() {
std::string demo_param = this->get_parameter("demo_param").as_string();
RCLCPP_INFO(this->get_logger(), "demo_param: %s", demo_param.c_str());
// Reset all parameters to prevent external modifications
std::vector<rclcpp::Parameter> all_parameters;
all_parameters.push_back(rclcpp::Parameter("demo_param", "set in cpp !!"));
this->set_parameters(all_parameters);
}
private:
rclcpp::TimerBase::SharedPtr timer_;
};
int main(int argc, char* argv[]) {
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MiniParam>());
rclcpp::shutdown();
return 0;
}
(4)编写 param_test_launch.py
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
Node(
package='parameters_cpp',
namespace='cpp',
executable='param_test',
name='param_test',
output="screen",
emulate_tty=True,
parameters=[
{"demo_param": "set in launch !!"}
]
)
])
(5)编写 param_monitor.cpp
#include <chrono>
#include <functional>
#include <string>
#include "rclcpp/rclcpp.hpp"
class MiniParam : public rclcpp::Node {
public:
MiniParam() : Node("param_monitor_cpp") {
// set param description
auto param_desc = rcl_interfaces::msg::ParameterDescriptor{};
param_desc.description = "This parameter is mine!";
this->declare_parameter("demo_param", "set in cpp !!", param_desc);
// used to monitor parameter changes
param_sub_ = std::make_shared<rclcpp::ParameterEventHandler>(this);
// 监测本节点的demo_param参数变化
demo_param_change_cb_ = param_sub_->add_parameter_callback("demo_param",
[this](const rclcpp::Parameter &p) {
RCLCPP_INFO(this->get_logger(), "received an update to : %s , type is %s, value is %s",
p.get_name().c_str(),
p.get_type_name().c_str(),
p.as_string().c_str());
});
// 监测/turtlesim_node节点的background_b参数变化
turtlesim_node_background_b_change_cb_ = param_sub_->add_parameter_callback("background_b",
[this](const rclcpp::Parameter &p) {
RCLCPP_INFO(this->get_logger(), "received an update to : %s , type is %s, value is %ld",
p.get_name().c_str(),
p.get_type_name().c_str(),
p.as_int());
}, "/turtlesim_node");
}
private:
std::shared_ptr<rclcpp::ParameterEventHandler> param_sub_;
std::shared_ptr<rclcpp::ParameterCallbackHandle> demo_param_change_cb_;
std::shared_ptr<rclcpp::ParameterCallbackHandle> turtlesim_node_background_b_change_cb_;
};
int main(int argc, char* argv[]) {
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MiniParam>());
rclcpp::shutdown();
return 0;
}
(6)编写 param_monitor_launch.py
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.actions import TimerAction
def generate_launch_description():
return LaunchDescription([
# 监控这个节点的参数变化
Node(
package='turtlesim',
executable='turtlesim_node',
name='turtlesim_node',
output="screen",
emulate_tty=True
),
TimerAction(
period=3.0,
actions=[
Node(
package='parameters_cpp',
namespace='cpp',
executable='param_monitor',
name='param_monitor',
output="screen",
emulate_tty=True
)
]
)
])
(7)编写CmakeLists.txt
cmake_minimum_required(VERSION 3.8)
project(parameters_cpp)
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_test src/param_test.cpp)
ament_target_dependencies(param_test rclcpp)
add_executable(param_monitor src/param_monitor.cpp)
ament_target_dependencies(param_monitor rclcpp)
install(TARGETS
param_test
param_monitor
DESTINATION lib/${PROJECT_NAME})
install(DIRECTORY
launch
DESTINATION share/${PROJECT_NAME}
)
ament_package()
(8)测试 param_test
~/colcon_ws
colcon build --packages-select parameters_cpp
source install/local_setup.bash
ros2 launch parameters_cpp param_test_launch.py
# 新开一个窗口,使用命令行修改参数
~/colcon_ws
source install/local_setup.bash
ros2 param set /cpp/param_test demo_param hahaharos2
(9)测试 param_monitor
~/colcon_ws
colcon build --packages-select parameters_cpp
source install/local_setup.bash
ros2 launch parameters_cpp param_monitor_launch.py
# 新开一个窗口,使用命令行修改参数
~/colcon_ws
source install/local_setup.bash
ros2 param set /cpp/param_monitor demo_param hahaharos2
ros2 param set /turtlesim_node background_b 134
2.2 parameters_py
(1)功能介绍:parameters_py 的功能与 parameters_cpp 基本相同,唯一的区别是没有实现监控其他节点( /turtlesim_node )参数的变化,主要是 python 实现这个功能非常复杂,暂时不搞了。
(2)请读者到本人 github 上获取源码:parameters_py,这里不再详述 parameters_py 的编码和测试过程,直接放运行截图:
3 总结
本文源码托管在本人的github上:parameters_cpp,parameters_py