開始之前先來複習一下
ROS
和ROS2
Parameter的機制,會讓在Migrating的人更好理解,不然當初我寫的時候都一頭霧水。首先ROS2
已經沒有Master Server,所以Parameter Server也一起消失了。這樣的好處是可以隨時啟動node不用先跑roscore
。但是這也意味著Parameter必須依賴Node,必須在Node內被宣告後才能在使用。這也是為什麼
ROS
中我們可以直接用get_param
來取得參數,但是ROS2
必須要先declare_parameter
然後再get_parameter
才能取得參數。接下來我們來看看ROS2
的Parameter怎麼用。
首先我們建立一個新的c++ package,並且加入rclcpp
的dependency:
ros2 pkg create --build-type ament_cmake cpp_parameters --dependencies rclcpp
在ros2_ws/src/cpp_parameters/src
底下新增cpp_parameters_node.cpp
:
#include <chrono>
#include <functional>
#include <string>
#include <rclcpp/rclcpp.hpp>
using namespace std::chrono_literals;
class MinimalParam : public rclcpp::Node
{
public:
MinimalParam()
: Node("minimal_param_node")
{
this->declare_parameter("my_parameter", "world");
timer_ = this->create_wall_timer(
1000ms, std::bind(&MinimalParam::timer_callback, this));
}
void timer_callback()
{
std::string my_param = this->get_parameter("my_parameter").as_string();
RCLCPP_INFO(this->get_logger(), "Hello %s!", my_param.c_str());
std::vector<rclcpp::Parameter> all_new_parameters{rclcpp::Parameter("my_parameter", "world")};
this->set_parameters(all_new_parameters);
}
private:
rclcpp::TimerBase::SharedPtr timer_;
};
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalParam>());
rclcpp::shutdown();
return 0;
}
解析:
class MinimalParam : public rclcpp::Node
{
public:
MinimalParam()
: Node("minimal_param_node")
{
this->declare_parameter("my_parameter", "world");
timer_ = this->create_wall_timer(
1000ms, std::bind(&MinimalParam::timer_callback, this));
}
首先來看Constructor。在ROS2
中,必須要先declare_parameter
才能使用get_parameter
,所以先在這裡宣告一個my_parameter
,並且給他預設值world
。接著建立一個timer,每秒鐘會呼叫timer_callback
。
void timer_callback()
{
std::string my_param = this->get_parameter("my_parameter").as_string();
RCLCPP_INFO(this->get_logger(), "Hello %s!", my_param.c_str());
std::vector<rclcpp::Parameter> all_new_parameters{rclcpp::Parameter("my_parameter", "world")};
this->set_parameters(all_new_parameters);
}
在timer_callback
中,我們先用get_parameter
取得my_parameter
的值,並且用RCLCPP_INFO
印出來。接著建立一個std::vector
,並且用set_parameters
來設定my_parameter
的值返回為world
。這樣使用者在外部更改my_parameter
的值,timer_callback
就會將他改回world
。
這邊用的set_parameters
可以一次用來設定多個參數。當然也可以用set_parameter
來設定單一參數。set_parameters
的用法如下:
this->set_parameter(rclcpp::Parameter("my_parameter", "world"));
其餘的用法都和前面的範例一樣,smart pointer宣告node,rclcpp::init
和rclcpp::shutdown
來啟動和關閉node,就不再贅述。
在CMakeLists.txt
的find_package(rclcpp REQUIRED)
下方加入:
add_executable(minimal_param_node src/cpp_parameters_node.cpp)
ament_target_dependencies(minimal_param_node rclcpp)
install(TARGETS
minimal_param_node
DESTINATION lib/${PROJECT_NAME}
)
可以看到我們並沒有增新的dependency,因為parameter是rclcpp
的一部分。
Build:
cd ~/ros2_ws
# install dependencies (if any)
rosdep install -i --from-path src --rosdistro foxy -y
colcon build --packages-select cpp_parameters
source install/setup.bash
執行:
ros2 run cpp_parameters minimal_param_node
就可以看到:
[INFO] [1630549430.000000000] [minimal_param_node]: Hello world!
開一個新的terminal查看parameter:
ros2 param list
可以看到:
my_parameter
接著將world
換成其他字,像是there
ros2 param set /minimal_param_node my_parameter there
再回到第一個terminal,可以看到成功更改world
:
[INFO] [minimal_param_node]: Hello there!
當然也可以在launch file中更改parameter:
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
Node(
package="cpp_parameters",
executable="minimal_param_node",
name="custom_minimal_param_node",
output="screen",
emulate_tty=True,
parameters=[
{"my_parameter": "there"}
]
)
])
ros launch 的部分後面會再詳細介紹,這邊只要知道Node
中的parameters=[]
可以用來設定參數就好。
CMakeLists.txt
中安裝launch
:
install(
DIRECTORY launch
DESTINATION share/${PROJECT_NAME}
)
colcon build --symlink-install --packages-select cpp_parameters
source install/setup.bash
這邊用--symlink-install
是因為我們要修改src
底下得launch file,這樣可以讓install
內的launch file也跟著改變。ros2 launch cpp_parameters cpp_parameters_launch.py
可以看到更改成功:
[INFO] [minimal_param_node]: Hello there!
大致上都和C++範例的架構一樣,不過Python的人會跳過XDD 這邊再說一次好了。
在ros2_ws/src
底下新增一個python package:
ros2 pkg create --build-type ament_python python_parameters --dependencies rclpy
在ros2_ws/src/python_parameters/python_parameters
底下新增python_parameters_node.py
:
import rclpy
import rclpy.node
class MinimalParam(rclpy.node.Node):
def __init__(self):
super().__init__('minimal_param_node')
self.declare_parameter('my_parameter', 'world')
self.timer = self.create_timer(1, self.timer_callback)
def timer_callback(self):
my_param = self.get_parameter('my_parameter').get_parameter_value().string_value
self.get_logger().info('Hello %s!' % my_param)
my_new_param = rclpy.parameter.Parameter(
'my_parameter',
rclpy.Parameter.Type.STRING,
'world'
)
all_new_parameters = [my_new_param]
self.set_parameters(all_new_parameters)
def main():
rclpy.init()
node = MinimalParam()
rclpy.spin(node)
if __name__ == '__main__':
main()
先看__init__
的部分
def __init__(self):
super().__init__('minimal_param_node')
self.declare_parameter('my_parameter', 'world')
self.timer = self.create_timer(1, self.timer_callback)
先宣告一個my_parameter
,並且給他預設值world
。接著建立一個timer,每秒鐘會呼叫timer_callback
。
def timer_callback(self):
my_param = self.get_parameter('my_parameter').get_parameter_value().string_value
self.get_logger().info('Hello %s!' % my_param)
my_new_param = rclpy.parameter.Parameter(
'my_parameter',
rclpy.Parameter.Type.STRING,
'world'
)
all_new_parameters = [my_new_param]
self.set_parameters(all_new_parameters)
在timer_callback
中,我們先用get_parameter
取得my_parameter
的值,並且用self.get_logger().info
印出來。接著建立一個rclpy.parameter.Parameter
,並且用set_parameters
來設定my_parameter
的值返回為world
。這樣使用者在外部更改my_parameter
的值,timer_callback
就會將他改回world
。
注意這邊和C++不同的是,rclpy.parameter.Parameter
必須要給他rclpy.Parameter.Type
,這邊我們給他STRING
。
其餘的部分和C++範例一樣,rclpy.init
和rclpy.spin
來啟動和關閉node。
加入entry point到setup.py
:
entry_points={
'console_scripts': [
'minimal_param_node = python_parameters.python_parameters_node:main',
],
},
Build:
cd ~/ros2_ws
rosdep install -i --from-path src --rosdistro foxy -y
colcon build --symlink-install --packages-select python_parameters
source install/setup.bash
執行:
ros2 run python_parameters minimal_param_node
就可以看到:
[INFO] [minimal_param_node]: Hello world!
開一個新的terminal查看parameter:
ros2 param list
可以看到:
my_parameter
接著將world
換成其他字,像是there
ros2 param set /minimal_param_node my_parameter there
再回到第一個terminal,可以看到成功更改world
:
[INFO] [minimal_param_node]: Hello there!
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
Node(
package='python_parameters',
executable='minimal_param_node',
name='custom_minimal_param_node',
output='screen',
emulate_tty=True,
parameters=[
{'my_parameter': 'there'}
]
)
])
setup.py
加入launch
:
import os
from glob import glob
# ...
setup(
# ...
data_files=[
# ...
(os.path.join('share', package_name), glob('launch/*launch.[pxy][yma]*')),
]
)
cd ~/ros2_ws
colcon build --symlink-install --packages-select python_parameters
source install/setup.bash
ros2 launch python_parameters python_parameters_launch.py
可以看到更改成功:
[INFO] [minimal_param_node]: Hello there!
說明 | ROS | ROS2 |
---|---|---|
Parameter Server | 有 | 無 |
Accessibility | 全域或namespace | 僅Node內部 |
Parameter 取得 | nh.getParam |
1. node->declare_parameter 2. node->get_parameter |
Parameter 設定 | nh.setParam |
1. node->declare_parameter 2. node->set_parameter |
run 指令 | rosrun pkg node _param:=value |
ros2 run pkg node --ros-args -p param:=value |
Check Parameter | rosparam list |
ros2 param list |
Set Parameter | rosparam set (/ns)/param value |
ros2 param set /node param value |
Get Parameter | rosparam get (/ns)/param |
ros2 param get /node param |
Parameter Exists API | nh.hasParam |
node->list_parameters |