Skip to content

Commit

Permalink
rename of x500_lidar to x_500_lidar_2d
Browse files Browse the repository at this point in the history
  • Loading branch information
Claudio-Chies committed Nov 1, 2024
1 parent 308dd27 commit a2d3f9e
Show file tree
Hide file tree
Showing 3 changed files with 30 additions and 2 deletions.
3 changes: 1 addition & 2 deletions models/lidar_2d_v2/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@
</mesh>
</geometry>
</visual>
<sensor name="lidar_2d_v2" type="gpu_ray">
<sensor name="lidar_2d_v2" type="gpu_lidar">
<pose>0 0 0.055 0 0 0</pose>
<ray>
<scan>
Expand All @@ -73,7 +73,6 @@
<update_rate>30</update_rate>
<visualize>false</visualize>
</sensor>

</link>
</model>
</sdf>
11 changes: 11 additions & 0 deletions models/x500_lidar_2d/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
<?xml version="1.0"?>
<model>
<name>x500_lidar_2d</name>
<version>1.0</version>
<sdf version="1.9">model.sdf</sdf>
<author>
<name>Jacob Dahl</name>
<email>[email protected]</email>
</author>
<description>x500 model with 2D Scanning Lidar</description>
</model>
18 changes: 18 additions & 0 deletions models/x500_lidar_2d/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version='1.9'>
<model name='x500_lidar_2d'>
<include merge='true'>
<uri>x500</uri>
</include>
<include merge='true'>
<!-- <uri>https://fuel.gazebosim.org/1.0/OpenRobotics/models/Lidar 2d v2</uri> -->
<uri>model://lidar_2d_v2</uri>
<pose>.12 0 .26 0 0 0</pose>
</include>
<joint name="LidarJoint" type="fixed">
<parent>base_link</parent>
<child>link</child>
<pose relative_to="base_link">-.1 0 .26 0 0 0</pose>
</joint>
</model>
</sdf>

0 comments on commit a2d3f9e

Please sign in to comment.