はじめに
ROS1では、パラメータサーバーが全てのノード間で共有されていたため1つのuse_sim_timeを切り替えると全体のNodeに適応されていたが、ROS2ではパラメータは各ノードによって個別に管理されるようになったため、use_sim_timeを個別に設定する必要があり、use_sim_timeを切り替えるのが面倒になった。
launchのargmentでuse_sim_timeを設定し、launch内の全Nodeのuse_sim_timeを切り替えるPython launchの書き方の例
launchファイルの例
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
def generate_launch_description():
pkg_share = get_package_share_directory('sample')
use_sim_time_arg = DeclareLaunchArgument(
'use_sim_time', default_value='true')
use_sim_time = LaunchConfiguration('use_sim_time')
navsat_transform_node = Node(
package='robot_localization',
executable='navsat_transform_node',
name='navsat_transform_node',
output='screen',
parameters=[{
"magnetic_declination_radians": 0.0,
"zero_altitude": True,
"wait_for_datum": False,
"publish_filtered_gps": False,
"broadcast_utm_transform": False,
"use_odometry_yaw": False,
"use_sim_time": use_sim_time,
}]
)
ekf_localization_node = Node(
package='robot_localization',
executable='ekf_node',
name='ekf_node',
output='screen',
respawn=True,
parameters=[os.path.join(pkg_share, 'config/ekf.yaml'), {'use_sim_time': use_sim_time}],
)
return LaunchDescription(
[
use_sim_time_arg,
ekf_localization_node,
navsat_transform_node,
]
)
以下launchの説明
use_sim_time_arg = DeclareLaunchArgument(
'use_sim_time', default_value='true')
use_sim_time = LaunchConfiguration('use_sim_time')
DeclareLaunchArgumentでlaunch引数を宣言し、使いやすいようにuse_sim_timeという変数にLaunchConfigurationで取得した状態を入れておく。
直接launchファイル内にパラメータを書く場合
parametersにuse_sim_timeを追加する
navsat_transform_node = Node(
package='robot_localization',
executable='navsat_transform_node',
name='navsat_transform_node',
output='screen',
parameters=[{
"magnetic_declination_radians": 0.0,
"zero_altitude": True,
"wait_for_datum": False,
"publish_filtered_gps": False,
"broadcast_utm_transform": False,
"use_odometry_yaw": False,
"use_sim_time": use_sim_time,
}]
)
yaml ファイルからパラメータを読む場合
ekf_localization_node = Node(
package='robot_localization',
executable='ekf_node',
name='ekf_node',
output='screen',
respawn=True,
parameters=[os.path.join(pkg_share, 'config/ekf.yaml'), {'use_sim_time': use_sim_time}],
)
最後に忘れずにLaunchArgumentもLaunchDescriptionに追加しておく
return LaunchDescription(
[
use_sim_time_arg,
ekf_localization_node,
navsat_transform_node,
]
使い方
use_sim_timeをtrueにする場合
ros2 launch sample sample.launch.py use_sim_time:=true
use_sim_timeをfalseにする場合
ros2 launch sample sample.launch.py use_sim_time:=false
おわりに
最近はyaml, xmlでlaunchファイルを書く人も多いので、Python以外でもできたら後日追記したい。
参考