Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Support validating target reports through image stream #59

Merged
merged 6 commits into from
Mar 29, 2022

Conversation

iche033
Copy link
Collaborator

@iche033 iche033 commented Mar 9, 2022

Depends on gazebosim/gz-sim#1381

Targets are to be reported by labeling their location in a live video stream. This PR adds the following functionality:

  • ign service to indicate a stream has started
  • ign service for reporting the target location (image 2d pos) in the image stream
  • validate the reported image pos contains a valid target

The GameLogic plugin does not actually process any incoming video images, e.g. no object recognition or image processing, etc but instead it uses the rendering engine to check if target objects are in the camera view (by checking target is within frustum and projecting ray to see if it hits the target)

To test, I find it easiest to make the UAV static first so it does not fall when we hover it over the target, e.g.

diff --git a/mbzirc_ign/models/mbzirc_quadrotor/model.sdf.erb b/mbzirc_ign/models/mbzirc_quadrotor/model.sdf.erb
index 838c1b4..51960c3 100644
--- a/mbzirc_ign/models/mbzirc_quadrotor/model.sdf.erb
+++ b/mbzirc_ign/models/mbzirc_quadrotor/model.sdf.erb
@@ -75,6 +75,7 @@ end
 <?xml version="1.0"?>
 <sdf version='1.9'>
   <model name="<%= $model_name%>">
+    <static>true</static>

Make sure to build and install the workspace.

  1. Launch simple demo world:

    ros2 launch ros_ign_gazebo ign_gazebo.launch.py ign_args:="-v 4 -r simple_demo.sdf"
  2. spawn quadrotor with downward looking camera:

    # slot3 is downward looking camera
    ros2 launch mbzirc_ign spawn.launch.py name:=quadrotor_1 world:=simple_demo model:=mbzirc_quadrotor type:=uav x:=-0 y:=0 z:=1.2 R:=0 P:=0 Y:=0 slot3:=mbzirc_hd_camera
  3. Move the quadrotor above vessel:

    # adjust your x and y pos accordingly since vessel may move due to wave and wind
    ign service -s /world/simple_demo/set_pose --reqtype ignition.msgs.Pose --reptype ignition.msgs.Boolean --timeout 300 --req 'name: "quadrotor_1", position: {x: 25.0, y:25, z:80}'
  4. Use ign service to indicate that stream is to be started

    # string args are: name of vehicle and sensor producing the video stream
    ign service -s /mbzirc/target/stream/start --reqtype ignition.msgs.StringMsg_V --reptype ignition.msgs.Boolean --timeout 300 --req 'data: ["quadrotor_1", "sensor_3"]'
  5. Use ign service to report target vessel in stream

    # 640, 480 is center of image
    ign service -s /mbzirc/target/stream/report --reqtype ignition.msgs.StringMsg_V --reptype ignition.msgs.Boolean --timeout 300 --req 'data: ["vessel", "640", "480"]'
  6. Open /tmp/ign/mbzirc/logs/events.yml to see that the vessel is successfully reported. You should see an event with data: vessel_id_success

  7. Repeat the process for small and large target objects

    # adjust your x and y pos accordingly since vessel may move due to wave and wind
    # set low z pos so it can see the obj without hitting the mainsail part of the boat
    ign service -s /world/simple_demo/set_pose --reqtype ignition.msgs.Pose --reptype ignition.msgs.Boolean --timeout 300 --req 'name: "quadrotor_1", position: {x: 24.0, y:26.5, z:2}'
    
    ign service -s /mbzirc/target/stream/report --reqtype ignition.msgs.StringMsg_V --reptype ignition.msgs.Boolean --timeout 300 --req 'data: ["small", "640", "480"]'
    
    ign service -s /world/simple_demo/set_pose --reqtype ignition.msgs.Pose --reptype ignition.msgs.Boolean --timeout 300 --req 'name: "quadrotor_1", position: {x: 24.90, y:24.85, z:2}'
    
    ign service -s /mbzirc/target/stream/report --reqtype ignition.msgs.StringMsg_V --reptype ignition.msgs.Boolean --timeout 300 --req 'data: ["large", "640", "480"]'
  8. You can also try reporting wrong image pos and you should see *_object_id_success_* events logged. Simulation stops after 3 invalid attempts.

mbzirc_ign/src/GameLogicPlugin.cc Outdated Show resolved Hide resolved
mbzirc_ign/src/GameLogicPlugin.cc Show resolved Hide resolved
Signed-off-by: Ian Chen <[email protected]>
Copy link
Collaborator

@caguero caguero left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I got this error message when running step 7 of your instructions:

caguero@cold:~/mbzirc_ws$ ign service -s /world/simple_demo/set_pose --reqtype ignition.msgs.Pose --reptype ignition.msgs.Boolean --timeout 300 --req 'name: "quadrotor_1", position: {x: 24.9.0, y:24.85, z:2}'
[libprotobuf ERROR google/protobuf/text_format.cc:307] Error parsing text-format ignition.msgs.Pose: 1:40: Already saw decimal point or exponent; can't have another one.
[libprotobuf ERROR google/protobuf/text_format.cc:307] Error parsing text-format ignition.msgs.Pose: 1:40: Expected identifier, got: .0
data: true

and this is the content of the events file:

caguero@cold:~/mbzirc_ws$ tail -f /tmp/ign/mbzirc/logs/events.yml
  total_score: 48
  data: vessel::640::480
- event:
  id: 3
  type: target_reported
  time_sec: 83
  elapsed_real_time: 54
  elapsed_sim_time: 48
  total_score: 48
  data: vessel_id_success
- event:
  id: 4
  type: target_reported_in_stream
  time_sec: 116
  elapsed_real_time: 91
  elapsed_sim_time: 81
  total_score: 80
  data: small::640::480
- event:
  id: 5
  type: target_reported
  time_sec: 116
  elapsed_real_time: 91
  elapsed_sim_time: 81
  total_score: 261
  data: small_object_id_failure_1
- event:
  id: 6
  type: target_reported_in_stream
  time_sec: 128
  elapsed_real_time: 105
  elapsed_sim_time: 93
  total_score: 273
  data: large::640::480
- event:
  id: 7
  type: target_reported
  time_sec: 128
  elapsed_real_time: 105
  elapsed_sim_time: 93
  total_score: 453
  data: large_object_id_failure_1

I see a few object_id_failure. Is this expected?

@caguero
Copy link
Collaborator

caguero commented Mar 23, 2022

I got this error message when running step 7 of your instructions:

caguero@cold:~/mbzirc_ws$ ign service -s /world/simple_demo/set_pose --reqtype ignition.msgs.Pose --reptype ignition.msgs.Boolean --timeout 300 --req 'name: "quadrotor_1", position: {x: 24.9.0, y:24.85, z:2}'
[libprotobuf ERROR google/protobuf/text_format.cc:307] Error parsing text-format ignition.msgs.Pose: 1:40: Already saw decimal point or exponent; can't have another one.
[libprotobuf ERROR google/protobuf/text_format.cc:307] Error parsing text-format ignition.msgs.Pose: 1:40: Expected identifier, got: .0
data: true

and this is the content of the events file:

caguero@cold:~/mbzirc_ws$ tail -f /tmp/ign/mbzirc/logs/events.yml
  total_score: 48
  data: vessel::640::480
- event:
  id: 3
  type: target_reported
  time_sec: 83
  elapsed_real_time: 54
  elapsed_sim_time: 48
  total_score: 48
  data: vessel_id_success
- event:
  id: 4
  type: target_reported_in_stream
  time_sec: 116
  elapsed_real_time: 91
  elapsed_sim_time: 81
  total_score: 80
  data: small::640::480
- event:
  id: 5
  type: target_reported
  time_sec: 116
  elapsed_real_time: 91
  elapsed_sim_time: 81
  total_score: 261
  data: small_object_id_failure_1
- event:
  id: 6
  type: target_reported_in_stream
  time_sec: 128
  elapsed_real_time: 105
  elapsed_sim_time: 93
  total_score: 273
  data: large::640::480
- event:
  id: 7
  type: target_reported
  time_sec: 128
  elapsed_real_time: 105
  elapsed_sim_time: 93
  total_score: 453
  data: large_object_id_failure_1

I see a few object_id_failure. Is this expected?

Oh, I see, there's a typo. Let me try again.

@caguero
Copy link
Collaborator

caguero commented Mar 23, 2022

```shell
ign service -s /mbzirc/target/stream/report --reqtype ignition.msgs.StringMsg_V --reptype ignition.msgs.Boolean --timeout 300 --req 'data: ["large", "640", "480"]'

I still see an data: small_object_id_failure_1 and large_object_id_failure_1.

@caguero
Copy link
Collaborator

caguero commented Mar 23, 2022

Oh, I see, there's a typo. Let me try again.

Should this line in the instructions

ign service -s /world/simple_demo/set_pose --reqtype ignition.msgs.Pose --reptype ignition.msgs.Boolean --timeout 300 --req 'name: "quadrotor_1", position: {x: 24.9.0, y:24.85, z:2}'

be

ign service -s /world/simple_demo/set_pose --reqtype ignition.msgs.Pose --reptype ignition.msgs.Boolean --timeout 300 --req 'name: "quadrotor_1", position: {x: 24.90, y:24.85, z:2}'

?

@iche033
Copy link
Collaborator Author

iche033 commented Mar 23, 2022

ah thanks for fixing the typos.

I still see an data: small_object_id_failure_1 and large_object_id_failure_1.

I think that's because the USV and objects have moved (due to wind and waves). Could you try opening Image Display gui plugin and see if they objects are in the center of the camera view before invoking the service call? If not, you'll need to tweak the UAV position so that the objects are positioned in the center of the image (or specify different image coordinates which is harder to do).

@caguero
Copy link
Collaborator

caguero commented Mar 24, 2022

I confirm that I get a successful confirmation when the objects are centered in the image.

- event:
  id: 4
  type: target_reported_in_stream
  time_sec: 46
  elapsed_real_time: 35
  elapsed_sim_time: 30
  total_score: 30
  data: small::640::480
- event:
  id: 5
  type: target_reported
  time_sec: 46
  elapsed_real_time: 35
  elapsed_sim_time: 30
  total_score: 30
  data: small_object_id_success
- event:
  id: 6
  type: target_reported_in_stream
  time_sec: 56
  elapsed_real_time: 46
  elapsed_sim_time: 40
  total_score: 39
  data: large::640::480
- event:
  id: 7
  type: target_reported
  time_sec: 56
  elapsed_real_time: 46
  elapsed_sim_time: 40
  total_score: 39
  data: large_object_id_success

I changed the sea state and wind by running:

 ./set_sea_state.sh 0 --wind-dir 0 0 0

I think that's because the USV and objects have moved (due to wind and waves). Could you try opening Image Display gui plugin and see if they objects are in the center of the camera view before invoking the service call? If not, you'll need to tweak the UAV position so that the objects are positioned in the center of the image (or specify different image coordinates which is harder to do).

* disable robot when it moves out of outer geofence

Signed-off-by: Ian Chen <[email protected]>

* make robot static instead of halting its motion

Signed-off-by: Ian Chen <[email protected]>

* fix test

Signed-off-by: Ian Chen <[email protected]>

* update comments

Signed-off-by: Ian Chen <[email protected]>

* Bridge competition topics (#62)

* publish phase, add competition launch file

Signed-off-by: Ian Chen <[email protected]>

* fix and add test

Signed-off-by: Ian Chen <[email protected]>
@iche033 iche033 merged commit ba6d75e into main Mar 29, 2022
@iche033 iche033 deleted the target_stream_confirmation branch March 29, 2022 03:53
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants