Skip to content

Commit

Permalink
Update cloudship.sdf.jinja
Browse files Browse the repository at this point in the history
Replace GPS joint with statement including GPS joint defined in other GPS model folder. This is adapted from the method that other Gazebo SITL models include the GPS such as the plane. The base_link term is replaced by hull to attach the GPS to the hull.
  • Loading branch information
JamesAnawati authored and Jaeyoung-Lim committed Mar 22, 2022
1 parent 25138e8 commit b3ab8de
Showing 1 changed file with 9 additions and 47 deletions.
56 changes: 9 additions & 47 deletions models/cloudship/cloudship.sdf.jinja
Original file line number Diff line number Diff line change
Expand Up @@ -383,54 +383,16 @@
</geometry>
</collision>
</link>

<model name='gps0'>
<link name='link'>
<pose frame=''>0 0 0 0 0 0</pose>
<inertial>
<pose frame=''>0 0 0 0 0 0</pose>
<mass>0.01</mass>
<inertia>
<ixx>2.1733e-06</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>2.1733e-06</iyy>
<iyz>0</iyz>
<izz>1.8e-07</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<cylinder>
<radius>0.01</radius>
<length>0.002</length>
</cylinder>
</geometry>
<material>
<script>
<name>Gazebo/Black</name>
<uri>__default__</uri>
</script>
</material>
</visual>
<sensor name='gps' type='gps'>
<pose frame=''>0 0 0 0 0 0</pose>
<plugin name='gps_plugin' filename='libgazebo_gps_plugin.so'>
<robotNamespace/>
<gpsNoise>1</gpsNoise>
<gpsXYRandomWalk>2.0</gpsXYRandomWalk>
<gpsZRandomWalk>4.0</gpsZRandomWalk>
<gpsXYNoiseDensity>0.0002</gpsXYNoiseDensity>
<gpsZNoiseDensity>0.0004</gpsZNoiseDensity>
<gpsVXYNoiseDensity>0.2</gpsVXYNoiseDensity>
<gpsVZNoiseDensity>0.4</gpsVZNoiseDensity>
</plugin>
</sensor>
</link>
</model>
<joint name='gps0_joint' type='fixed'>

{# GPS joint which includes GPS plugin #}
<include>
<uri>model://gps</uri>
<pose>0 0 0 0 0 0</pose>
<name>gps</name>
</include>
<joint name='gps_joint' type='fixed'>
<child>gps::link</child>
<parent>hull</parent>
<child>gps0::link</child>
</joint>

{# Thrusters Rod #}
Expand Down

0 comments on commit b3ab8de

Please sign in to comment.