osrf / mbzirc

Simulator for the MBZIRC Maritime Grand Challenge
Apache License 2.0
72 stars 47 forks source link

Support changing video streams when reporting targets #195

Closed iche033 closed 2 years ago

iche033 commented 2 years ago

Signed-off-by: Ian Chen ichen@osrfoundation.org

Fixes https://github.com/osrf/mbzirc/issues/193

Depends on https://github.com/gazebosim/gz-rendering/pull/690

Currently target reporting only works with video stream from one camera. This PR adds support so that target report can be done from different cameras, e.g. verify vessel report from slot0 of quad_1 and then verify small object report from slot3 of quad_2.

To test:

  1. Apply the following patch make the quadrotor static and move Vessel B closer to coast and make it static so it's easier to test target reporting:

    patch ```diff diff --git a/mbzirc_ign/models/mbzirc_quadrotor/model.sdf.erb b/mbzirc_ign/models/mbzirc_quadrotor/model.sdf.erb index a16a8de..0cde58b 100644 --- a/mbzirc_ign/models/mbzirc_quadrotor/model.sdf.erb +++ b/mbzirc_ign/models/mbzirc_quadrotor/model.sdf.erb @@ -91,7 +91,7 @@ end - false + true diff --git a/mbzirc_ign/worlds/coast.sdf b/mbzirc_ign/worlds/coast.sdf index c44a64d..b7dc7e9 100644 --- a/mbzirc_ign/worlds/coast.sdf +++ b/mbzirc_ign/worlds/coast.sdf @@ -498,7 +498,7 @@ Vessel B - 0 0 0.4 0 0.0 0.0 + -1300 0 0.4 0 0.0 0.0 https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Vessel B 5 3 1.5 - 0.3 + 0.0 1 0 0.4 2.0 @@ -548,6 +548,7 @@ 0.0 + - - - 908 200 5 5 + --> @@ -1401,7 +1399,7 @@ - 0.3 0 0 + 0.0 0 0 ```
  2. build the workspace for changes to take place

    IGNITION_VERSION=fortress colcon build --merge-install
  3. Launch the coast environment

    ros2 launch mbzirc_ros competition_local.launch.py ign_args:="-v 4 -r coast.sdf"
  4. Spawn 2 quadrotors. One with front facing camera (slot0) and one with downward facing camera (slot3)

    ros2 launch mbzirc_ign spawn.launch.py name:=quadrotor_1 world:=coast model:=mbzirc_quadrotor x:=-1500 y:=2 z:=4.3 R:=0 P:=0 Y:=0 slot0:=mbzirc_hd_camera
    ros2 launch mbzirc_ign spawn.launch.py name:=quadrotor_2 world:=coast model:=mbzirc_quadrotor x:=-1500 y:=-2 z:=4.3 R:=0 P:=0 Y:=0 slot3:=mbzirc_hd_camera
  5. Position quadrotor_1 to look at vessel:

    ign service -s /world/coast/set_pose --reqtype ignition.msgs.Pose --reptype ignition.msgs.Boolean --timeout 300 --req 'name: "quadrotor_1", position: {x: -1310.0, y:0, z:1}'
  6. In another terminal, start stream from quadrotor_1 using image_transport

    ros2 run image_transport republish raw --ros-args --remap in:=/quadrotor_1/slot0/optical/image_raw --remap out:=/quadrotor_1/mbzirc/target/stream/start
  7. Report vessel

    ros2 topic pub --once /quadrotor_1/mbzirc/target/stream/report ros_ign_interfaces/msg/StringVec '{data: ["vessel", "640", "480"]}'

    Check tmp/ign/mbzirc/logs/events.yml and you should see vessel_id_success event

  8. Kill the stream (image_transport process) for quadrotor_1 by pressing Ctrl+C.

  9. Move quadrotor_2 above small target object

    ign service -s /world/coast/set_pose --reqtype ignition.msgs.Pose --reptype ignition.msgs.Boolean --timeout 300 --req 'name: "quadrotor_2", position: {x: -1300.35, y:1.6, z:1.6}'
  10. Start the stream from quadrotor_2

    ros2 run image_transport republish raw --ros-args --remap in:=/quadrotor_2/slot3/optical/image_raw --remap out:=/quadrotor_2/mbzirc/target/stream/start
  11. Report small object

    ros2 topic pub --once /quadrotor_2/mbzirc/target/stream/report ros_ign_interfaces/msg/StringVec '{data: ["small", "640", "480"]}'

    Verify that in tmp/ign/mbzirc/logs/events.yml, you see a small_object_id_success event