Skip to content

Commit

Permalink
matrice_100_opt_flow: overwrite model name of the sf10a lidar so the …
Browse files Browse the repository at this point in the history
…topic name is the expected from gazebo_mavlink_interface
  • Loading branch information
TSC21 committed Aug 18, 2019
1 parent 5f5e1ba commit a3b8b9c
Showing 1 changed file with 3 additions and 2 deletions.
5 changes: 3 additions & 2 deletions models/matrice_100_opt_flow/matrice_100_opt_flow.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -20,11 +20,12 @@
<include>
<uri>model://sf10a</uri>
<pose>0 0 -0.1 0 0 0</pose>
<name>lidar</name>
</include>

<joint name="sf10a_joint" type="fixed">
<joint name="lidar_joint" type="fixed">
<parent>iris::base_link</parent>
<child>sf10a::link</child>
<child>lidar::link</child>
</joint>

</model>
Expand Down

0 comments on commit a3b8b9c

Please sign in to comment.