Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
93 changes: 33 additions & 60 deletions simulation/models/achilles/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -46,79 +46,52 @@
</material>
</visual>

<sensor type="ray" name="us_left_sensor">
<pose>0.15 0.07 0.053 0 0 0.43633</pose>
<sensor type="sonar" name="us_left_sensor">
<pose>0.15 0.07 0.053 0 -1.5708 0.43633</pose>
<visualize>false</visualize>
<update_rate>5</update_rate>
<ray>
<scan>
<horizontal>
<samples>3</samples>
<resolution>1.0</resolution>
<min_angle>-.478</min_angle>
<max_angle>0.478</max_angle>
</horizontal>
</scan>
<range>
<min>0.010</min>
<max>3</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name="us" filename="libhector_gazebo_ros_sonar.so">
<gaussianNoise>0.005</gaussianNoise>
<sonar>
<min>0.01</min>
<max>3.0</max>
<radius>0.5</radius>
</sonar>
<plugin name="us" filename="libgazebo_plugins_sonar.so">
<gaussianNoise>0.15</gaussianNoise>
<topicName>/achilles/sonarLeft</topicName>
<frameId>achilles/us_left_link</frameId>
<frameName>achilles/us_left_link</frameName>
<fov>0.5</fov>
</plugin>
</sensor>
<sensor type="ray" name="us_right_sensor">
<pose>0.15 -0.07 0.053 0 0 -0.43633</pose>
<sensor type="sonar" name="us_right_sensor">
<pose>0.15 -0.07 0.053 0 -1.5708 -0.43633</pose>
<visualize>false</visualize>
<update_rate>5</update_rate>
<ray>
<scan>
<horizontal>
<samples>3</samples>
<resolution>1.0</resolution>
<min_angle>-.478</min_angle>
<max_angle>0.478</max_angle>
</horizontal>
</scan>
<range>
<min>0.010</min>
<max>3</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name="us" filename="libhector_gazebo_ros_sonar.so">
<gaussianNoise>0.005</gaussianNoise>
<sonar>
<min>0.01</min>
<max>3.0</max>
<radius>0.5</radius>
</sonar>
<plugin name="us" filename="libgazebo_plugins_sonar.so">
<gaussianNoise>0.15</gaussianNoise>
<topicName>/achilles/sonarRight</topicName>
<frameId>achilles/us_right_link</frameId>
<frameName>achilles/us_right_link</frameName>
<fov>0.5</fov>
</plugin>
</sensor>
<sensor type="ray" name="us_center_sensor">
<pose>0.15 0 0.053 0 0 0</pose>
<sensor type="sonar" name="us_center_sensor">
<pose>0.15 0 0.053 0 -1.5708 0</pose>
<visualize>false</visualize>
<update_rate>5</update_rate>
<ray>
<scan>
<horizontal>
<samples>3</samples>
<resolution>1.0</resolution>
<min_angle>-.478</min_angle>
<max_angle>0.478</max_angle>
</horizontal>
</scan>
<range>
<min>0.010</min>
<max>3</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name="us" filename="libhector_gazebo_ros_sonar.so">
<gaussianNoise>0.005</gaussianNoise>
<sonar>
<min>0.01</min>
<max>3.0</max>
<radius>0.5</radius>
</sonar>
<plugin name="us" filename="libgazebo_plugins_sonar.so">
<gaussianNoise>0.15</gaussianNoise>
<topicName>/achilles/sonarCenter</topicName>
<frameId>achilles/us_center_link</frameId>
<frameName>achilles/us_center_link</frameName>
<fov>0.5</fov>
</plugin>
</sensor>

Expand Down
93 changes: 33 additions & 60 deletions simulation/models/aeneas/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -46,79 +46,52 @@
</material>
</visual>

<sensor type="ray" name="us_left_sensor">
<pose>0.15 0.07 0.053 0 0 0.43633</pose>
<sensor type="sonar" name="us_left_sensor">
<pose>0.15 0.07 0.053 0 -1.5708 0.43633</pose>
<visualize>false</visualize>
<update_rate>5</update_rate>
<ray>
<scan>
<horizontal>
<samples>3</samples>
<resolution>1.0</resolution>
<min_angle>-.478</min_angle>
<max_angle>0.478</max_angle>
</horizontal>
</scan>
<range>
<min>0.010</min>
<max>3</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name="us" filename="libhector_gazebo_ros_sonar.so">
<gaussianNoise>0.005</gaussianNoise>
<sonar>
<min>0.01</min>
<max>3.0</max>
<radius>0.5</radius>
</sonar>
<plugin name="us" filename="libgazebo_plugins_sonar.so">
<gaussianNoise>0.15</gaussianNoise>
<topicName>/aeneas/sonarLeft</topicName>
<frameId>aeneas/us_left_link</frameId>
<frameName>aeneas/us_left_link</frameName>
<fov>0.5</fov>
</plugin>
</sensor>
<sensor type="ray" name="us_right_sensor">
<pose>0.15 -0.07 0.053 0 0 -0.43633</pose>
<sensor type="sonar" name="us_right_sensor">
<pose>0.15 -0.07 0.053 0 -1.5708 -0.43633</pose>
<visualize>false</visualize>
<update_rate>5</update_rate>
<ray>
<scan>
<horizontal>
<samples>3</samples>
<resolution>1.0</resolution>
<min_angle>-.478</min_angle>
<max_angle>0.478</max_angle>
</horizontal>
</scan>
<range>
<min>0.010</min>
<max>3</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name="us" filename="libhector_gazebo_ros_sonar.so">
<gaussianNoise>0.005</gaussianNoise>
<sonar>
<min>0.01</min>
<max>3.0</max>
<radius>0.5</radius>
</sonar>
<plugin name="us" filename="libgazebo_plugins_sonar.so">
<gaussianNoise>0.15</gaussianNoise>
<topicName>/aeneas/sonarRight</topicName>
<frameId>aeneas/us_right_link</frameId>
<frameName>aeneas/us_right_link</frameName>
<fov>0.5</fov>
</plugin>
</sensor>
<sensor type="ray" name="us_center_sensor">
<pose>0.15 0 0.053 0 0 0</pose>
<sensor type="sonar" name="us_center_sensor">
<pose>0.15 0 0.053 0 -1.5708 0</pose>
<visualize>false</visualize>
<update_rate>5</update_rate>
<ray>
<scan>
<horizontal>
<samples>3</samples>
<resolution>1.0</resolution>
<min_angle>-.478</min_angle>
<max_angle>0.478</max_angle>
</horizontal>
</scan>
<range>
<min>0.010</min>
<max>3</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name="us" filename="libhector_gazebo_ros_sonar.so">
<gaussianNoise>0.005</gaussianNoise>
<sonar>
<min>0.01</min>
<max>3.0</max>
<radius>0.5</radius>
</sonar>
<plugin name="us" filename="libgazebo_plugins_sonar.so">
<gaussianNoise>0.15</gaussianNoise>
<topicName>/aeneas/sonarCenter</topicName>
<frameId>aeneas/us_center_link</frameId>
<frameName>aeneas/us_center_link</frameName>
<fov>0.5</fov>
</plugin>
</sensor>

Expand Down
93 changes: 33 additions & 60 deletions simulation/models/ajax/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -46,79 +46,52 @@
</material>
</visual>

<sensor type="ray" name="us_left_sensor">
<pose>0.15 0.07 0.053 0 0 0.43633</pose>
<sensor type="sonar" name="us_left_sensor">
<pose>0.15 0.07 0.053 0 -1.5708 0.43633</pose>
<visualize>false</visualize>
<update_rate>5</update_rate>
<ray>
<scan>
<horizontal>
<samples>3</samples>
<resolution>1.0</resolution>
<min_angle>-.478</min_angle>
<max_angle>0.478</max_angle>
</horizontal>
</scan>
<range>
<min>0.010</min>
<max>3</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name="us" filename="libhector_gazebo_ros_sonar.so">
<gaussianNoise>0.005</gaussianNoise>
<sonar>
<min>0.01</min>
<max>3.0</max>
<radius>0.5</radius>
</sonar>
<plugin name="us" filename="libgazebo_plugins_sonar.so">
<gaussianNoise>0.15</gaussianNoise>
<topicName>/ajax/sonarLeft</topicName>
<frameId>ajax/us_left_link</frameId>
<frameName>ajax/us_left_link</frameName>
<fov>0.5</fov>
</plugin>
</sensor>
<sensor type="ray" name="us_right_sensor">
<pose>0.15 -0.07 0.053 0 0 -0.43633</pose>
<sensor type="sonar" name="us_right_sensor">
<pose>0.15 -0.07 0.053 0 -1.5708 -0.43633</pose>
<visualize>false</visualize>
<update_rate>5</update_rate>
<ray>
<scan>
<horizontal>
<samples>3</samples>
<resolution>1.0</resolution>
<min_angle>-.478</min_angle>
<max_angle>0.478</max_angle>
</horizontal>
</scan>
<range>
<min>0.010</min>
<max>3</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name="us" filename="libhector_gazebo_ros_sonar.so">
<gaussianNoise>0.005</gaussianNoise>
<sonar>
<min>0.01</min>
<max>3.0</max>
<radius>0.5</radius>
</sonar>
<plugin name="us" filename="libgazebo_plugins_sonar.so">
<gaussianNoise>0.15</gaussianNoise>
<topicName>/ajax/sonarRight</topicName>
<frameId>ajax/us_right_link</frameId>
<frameName>ajax/us_right_link</frameName>
<fov>0.5</fov>
</plugin>
</sensor>
<sensor type="ray" name="us_center_sensor">
<pose>0.15 0 0.053 0 0 0</pose>
<sensor type="sonar" name="us_center_sensor">
<pose>0.15 0 0.053 0 -1.5708 0</pose>
<visualize>false</visualize>
<update_rate>5</update_rate>
<ray>
<scan>
<horizontal>
<samples>3</samples>
<resolution>1.0</resolution>
<min_angle>-.478</min_angle>
<max_angle>0.478</max_angle>
</horizontal>
</scan>
<range>
<min>0.010</min>
<max>3</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name="us" filename="libhector_gazebo_ros_sonar.so">
<gaussianNoise>0.005</gaussianNoise>
<sonar>
<min>0.01</min>
<max>3.0</max>
<radius>0.5</radius>
</sonar>
<plugin name="us" filename="libgazebo_plugins_sonar.so">
<gaussianNoise>0.15</gaussianNoise>
<topicName>/ajax/sonarCenter</topicName>
<frameId>ajax/us_center_link</frameId>
<frameName>ajax/us_center_link</frameName>
<fov>0.5</fov>
</plugin>
</sensor>

Expand Down
Loading