ROS1 → ROS2 移行チュートリアル
対象読者
- ROS1で既にlaunchファイルやパラメータ設定を使っている方
- ROS2のlaunch記法やパラメータ管理に戸惑っている初心者〜中級者
1. 移行時の基本的な考え方
-
argument → configurationへ
- ROS1の
<arg>は、ROS2ではDeclareLaunchArgument+LaunchConfigurationで置き換える
- ROS1の
-
パラメータ管理
- ROS1は全体的にグローバルな管理
- ROS2はノードごとに独立管理(namespaceを合わせる必要あり)
-
スコープ管理
- ROS1はシンプルに
<group>でnamespaceを切り替え可能 - ROS2は
GroupAction(scoped=True)を利用してローカルスコープを作る
- ROS1はシンプルに
2. ROS1からROS2への書き換え例
(1) 基本的なlaunchファイル
ROS1の例
<launch>
<arg name="robot_name" default="turtlebot" />
<node pkg="my_robot" type="controller" name="controller" output="screen">
<param name="speed" value="1.0" />
<rosparam file="$(find my_robot)/config/params.yaml" command="load" />
</node>
</launch>
ROS2の例
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
# ROS1 <arg> → ROS2 DeclareLaunchArgument
DeclareLaunchArgument('robot_name', default_value='turtlebot'),
Node(
package='my_robot',
executable='controller',
name='controller',
output='screen',
parameters=[
{'speed': 1.0},
LaunchConfiguration('robot_name') # yamlやdictで渡すことも可能
]
)
])
✅ ポイント
-
$(find pkg)→FindPackageShareに置き換える -
rosparam load→parameters=[yamlファイルパス]に置き換える
(2) yamlファイルの読み込み
ROS1の例
<rosparam file="$(find my_robot)/config/controller.yaml" command="load" />
ROS2の例
from launch_ros.substitutions import FindPackageShare
from launch.substitutions import PathJoinSubstitution
config_file = PathJoinSubstitution([
FindPackageShare('my_robot'),
'config',
'controller.yaml'
])
Node(
package='my_robot',
executable='controller',
name='controller',
parameters=[config_file]
)
✅ ポイント
-
os.path.joinよりもPathJoinSubstitutionを使う方が好ましいが、PathJoinSubstitutionが使えないケース(文字列の結合等)もあるため使い分ける - yaml内のnamespaceをノード名と一致させる必要あり
- nav2_common.launch.RewrittenYamlを使うことでyamlファイルを動的に変更可能なので便利
(3) namespace付きlaunch
ROS1の例
<group ns="robot1">
<node pkg="my_robot" type="controller" name="controller" />
</group>
ROS2の例
from launch.actions import GroupAction
from launch_ros.actions import PushROSNamespace
GroupAction([
PushROSNamespace('robot1'),
Node(
package='my_robot',
executable='controller',
name='controller'
)
])
✅ ポイント
- ROS2では
PushROSNamespaceを使う - ノード毎に引数で指定することもできる
- ローカル変数化したい場合は
GroupAction(scoped=True)を利用
3. パラメータ設定の移行
ROS1のyaml
controller:
speed: 1.0
max_angle: 45
ROS2のyaml
controller:
ros__parameters:
speed: 1.0
max_angle: 45
✅ ポイント
-
ros__parameters:が必須 - ネストを利用してグループ化可能
4. ROS1→ROS2移行のチェックリスト
-
<arg>をDeclareLaunchArgumentに置き換えたか -
$(find ...)をFindPackageShareに置き換えたか -
os.path.joinをPathJoinSubstitutionに置き換えたか -
yamlに
ros__parametersを追加したか - namespaceがノード名と一致しているか
-
パラメータを辞書型で扱う場合は
get_parameters_by_prefixを利用しているか
まとめ
- ROS2は「グローバル変数的」だったROS1のlaunch記法を、「スコープ付きの変数管理」と「ノード単位のパラメータ管理」に整理した仕様
- 書き方はやや冗長だが、substitution・namespace・scopingを正しく使い分けることで柔軟なlaunch構成が可能