Artefacts ツールキットの Gazebo ヘルパー
Artefacts ツールキットの Gazebo ヘルパーは、テスト実行中に Gazebo シミュレーションとやり取りするための便利な関数を提供します。これらのユーティリティを使用すると、シミュレーションオブジェクトの検査、モデル位置へのアクセス、および Gazebo と ROS2 間のトピックブリッジングが可能になります。
インポート方法:
from artefacts_toolkit.gazebo import bridge, gz
関数
関数リファレンス
bridge.get_camera_bridge
カメラトピック用の gazebo / ros2 トピックブリッジを作成します。
bridge.get_camera_bridge(
topic_name,
condition=None
)
パラメータ
パラメータ | 型 | 説明 | デフォルト |
---|---|---|---|
topic_name |
str |
Gazebo から ROS2 へブリッジするカメラトピック名 | 必須 |
condition |
str |
このブリッジを作成するタイミングを決定するオプションの起動条件 | None |
戻り値
Node
:指定されたカメラトピックの parameter_bridge を実行する ROS 2 Node オブジェクトを返します。このノードは起動記述に含めることができます。
Note
- このブリッジは、Gazebo の画像メッセージ (gz.msgs.Image) と ROS 2 の画像メッセージ (sensor_msgs/msg/Image) 間を変換します。
- 環境に ros_gz_bridge パッケージがインストールされている必要があります。
例
次の例では、起動引数に基づいて条件付きで作成されるカメラブリッジを示しています。record_video
が “true” に設定されている場合、ブリッジが有効になり、ROS 2 ノードが Gazebo からのカメラ画像をサブスクライブできるようになります。返された Node
は、起動プロセスに含めるために LaunchDescription に追加されます。
@pytest.mark.launch_test
def generate_test_description():
from artefacts_toolkit.gazebo import bridge
...
camera_topic = "/observation_camera/image"
bag_recorder, rosbag_filepath = get_bag_recorder([camera_topic])
sim = IncludeLaunchDescription(
PythonLaunchDescriptionSource(["bringup", "/robot.launch.py"])
)
record_video_launch_arg = DeclareLaunchArgument(
"record_video", default_value="true"
)
record_video = LaunchConfiguration("record_video")
camera_bridge = bridge.get_camera_bridge(camera_topic, condition=IfCondition(record_video))
return LaunchDescription(
[
record_video_launch_arg,
sim,
camera_bridge,
controller_process,
launch_testing.actions.ReadyToTest(),
]
)
gz.get_sim_objects
XML 構造を解析することで Gazebo ワールドファイルからモデル情報を抽出します。この関数は、ワールドファイルで定義されているすべてのモデルの名前と元のポーズを返します。
これは、実行中のシミュレーションに問い合わせる(物理、ランダム性、または相互作用によって位置が変わっている可能性がある)よりも、ワールドファイルで定義されているモデルの初期ポーズを知る必要がある場合に便利です。
gz.get_sim_objects(world_file)
パラメータ
パラメータ | 型 | 説明 | デフォルト |
---|---|---|---|
world_file |
str |
解析する Gazebo ワールドファイルへのパス | 必須 |
戻り値
tuple
: この関数は、アンパックする必要がある2つの値を持つタプルを返します:
- 辞書のリスト:
objects = [
{
"name": "model_1",
"pose": "0 0 0 0 0 0"
},
{
"name": "model_2",
"pose": "1 2 3 0 0 0"
},
...
]
- モデル名からポーズへのマッピング辞書:
objects_positions = {
"model_1": "0 0 0 0 0 0",
"model_2": "1 2 3 0 0 0",
...
}
例
# Working with the objects_position dict
_, objects_positions = gz.get_sim_objects("world.sdf")
model_pose = objects_positions["model_1"] # "0 0 0 0 0 0"
# Working with the objects list
objects, _ = gz.get_sim_objects("world.sdf")
for model in objects:
print(f"{model['name']} is at position {model['pose']}")
gz.get_model_location
実行中の Gazebo シミュレーションでのモデルの現在の (x, y, z) 位置を取得します。ワールドファイルから元の位置を読み取る get_sim_objects
とは異なり、この関数はライブシミュレーションに問い合わせてモデルの現在の位置を取得します。
gz.get_model_location(model_name)
パラメータ
パラメータ | 型 | 説明 | デフォルト |
---|---|---|---|
model_name |
str |
シミュレーションで問い合わせるモデルの名前 | 必須 |
戻り値
tuple
:メートル単位の (x, y, z) 位置を表す3つの浮動小数点値のタプルを返します:
(x_position, y_position, z_position)
Note
- この関数には Gazebo シミュレーションが実行中である必要があります。
- モデル位置を特定できない場合は (0.0, 0.0, 0.0) を返します。
例
以下の例は、ピック&プレースタスクを検証するために get_sim_objects
と get_model_location
を組み合わせる方法を示しています。次の方法を示しています:
- ワールドファイルから初期位置を取得する
- ロボットがタスクを完了するのを待つ
- 初期位置と現在の位置を比較して、どのオブジェクトが移動したかを検出する
class TestProcOutput(unittest.TestCase):
def test_moved_meatballs(self, proc_output, controller_process):
# Original locations
sim_objects, sim_objects_positions = gz.get_sim_objects("worlds/env.sdf") # this includes models poses
meatball_models = [obj["name"] for obj in sim_objects if "karaage" in obj["name"]]
# Wait for the control loop to finish
proc_output.assertWaitFor("Done with tasks execution", timeout=300)
picked_meatballs = 0 # karaage moved for more than 10cm
for meatball in meatball_models:
x, y, z = gz.get_model_location(meatball)
x_original, y_original, z_original = sim_objects_positions[meatball]
dist = ((x - x_original) ** 2 + (y - y_original) ** 2 + (z - z_original) ** 2) ** 0.5
if dist > 0.1: #10cm
# Likely to have been picked and moved somewhere else
picked_meatballs += 1
self.assertEqual(picked_meatballs, 4)
gz.kill_gazebo
現在実行中の gazebo プロセスを強制終了します。
gz.kill_gazebo()
戻り値
None
: この関数は値を返しません。
例
from artefacts_toolkit.gazebo import gz
...
@launch_testing.post_shutdown_test()
class TestProcOutputAfterShutdown(unittest.TestCase):
def test_exit_code(self, proc_info, controller_process, rosbag_filepath):
gz.kill_gazebo()
...