Skip to content

Commit

Permalink
Zephyr: update parachute plugin name
Browse files Browse the repository at this point in the history
Signed-off-by: Rhys Mainwaring <[email protected]>
  • Loading branch information
srmainwaring committed Dec 20, 2023
1 parent 13fe557 commit be19414
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions worlds/zephyr_parachute.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@
SITL
====
sim_vehicle.py -D -v ArduPlane -f gazebo-zephyr \-\-model JSON \-\-map \-\-console
sim_vehicle.py -D -v ArduPlane -f gazebo-zephyr -\-model JSON -\-map -\-console
MAVProxy
========
Expand Down Expand Up @@ -206,7 +206,7 @@
<uri>model://zephyr_with_parachute</uri>
<pose degrees="true">0 0 0.422 -90 0 180</pose>

<plugin filename="libParachutePlugin.so" name="ParachutePlugin">
<plugin name="ParachutePlugin" filename="ParachutePlugin">
<parent_link>parachute_attachment_link</parent_link>
<child_model>parachute_small</child_model>
<child_link>chute</child_link>
Expand Down

0 comments on commit be19414

Please sign in to comment.