Skip to content

Commit

Permalink
X500 Lidar Models (#62)
Browse files Browse the repository at this point in the history
* added x500 model with frontfacing and downfacing lidar

* rename of x500_lidar to x_500_lidar_2d
  • Loading branch information
Claudio-Chies authored Nov 5, 2024
1 parent 448ef6f commit 9e47793
Show file tree
Hide file tree
Showing 10 changed files with 376 additions and 4 deletions.
170 changes: 170 additions & 0 deletions models/LW20/meshes/LW20.dae

Large diffs are not rendered by default.

21 changes: 21 additions & 0 deletions models/LW20/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
<?xml version="1.0"?>
<!--
IMPORTANT
This model just adds a Mesh, but no sensor
This is because the orientation of the gz message is the pose in respect the sensor link, and not in respect of the base_link
in GZBridge we can only read out the pose of the sensor link, so to be able to differentiate different sensor orientations, the sensor needs to be in the parent model.
-->
<model>
<name>LW20</name>
<version>1.0</version>
<sdf version="1.6">model.sdf</sdf>

<author>
<name>Claudio Chies</name>
<email>[email protected]</email>
</author>

<description>
A Lightware LW20/C Lidar Model
</description>
</model>
35 changes: 35 additions & 0 deletions models/LW20/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<model name="LW20">
<link name="lw20_link">
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.02</mass>
<inertia>
<ixx>0.000004</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000004</iyy>
<iyz>0</iyz>
<izz>0.000002</izz>
</inertia>
</inertial>
<collision name="collision_base">
<pose>0 0 0 0 0 0</pose>
<geometry>
<box>
<size>0.03 0.02 0.043</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://LW20/meshes/LW20.dae</uri>
</mesh>
</geometry>
</visual>
</link>
</model>
</sdf>
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>
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<model>
<name>x500-lidar</name>
<name>x500_lidar_2d</name>
<version>1.0</version>
<sdf version="1.9">model.sdf</sdf>
<author>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version='1.9'>
<model name='x500-lidar'>
<model name='x500_lidar_2d'>
<include merge='true'>
<uri>x500</uri>
</include>
Expand Down
11 changes: 11 additions & 0 deletions models/x500_lidar_down/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
<?xml version="1.0"?>
<model>
<name>x500_lidar_down</name>
<version>1.0</version>
<sdf version="1.9">model.sdf</sdf>
<author>
<name>Claudio Chies</name>
<email>[email protected]</email>
</author>
<description>An x500 a lidar pointing down.</description>
</model>
63 changes: 63 additions & 0 deletions models/x500_lidar_down/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version='1.9'>
<model name='x500_lidar_down'>
<self_collide>false</self_collide>
<include merge='true'>
<uri>x500</uri>
</include>
<include merge='true'>
<uri>model://LW20</uri>
<pose relative_to="base_link">0 0 -0.079 0 1.57 0</pose>
</include>
<joint name="lidar_model_joint" type="fixed">
<parent>base_link</parent>
<child>lw20_link</child>
<pose relative_to="base_link">-0 0 0 0 0 0</pose>
</joint>
<joint name="lidar_sensor_joint" type="fixed">
<parent>base_link</parent>
<child>lidar_sensor_link</child>
</joint>
<link name="lidar_sensor_link">
<pose relative_to="base_link">0 0 -0.05 0 1.57 0</pose>
<inertial>
<mass>0.001</mass>
<inertia>
<ixx>0.00001</ixx>
<iyy>0.00001</iyy>
<izz>0.00001</izz>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
</inertia>
</inertial>
<sensor name='lidar' type='gpu_lidar'>"
<pose>0 0 0 3.14 0 0</pose>
<update_rate>50</update_rate>
<ray>
<scan>
<horizontal>
<samples>1</samples>
<resolution>1</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</horizontal>
<vertical>
<samples>1</samples>
<resolution>1</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</vertical>
</scan>
<range>
<min>0.1</min>
<max>100.0</max>
<resolution>0.01</resolution>
</range>
</ray>
<always_on>1</always_on>
<visualize>true</visualize>
</sensor>
</link>
</model>
</sdf>
11 changes: 11 additions & 0 deletions models/x500_lidar_front/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
<?xml version="1.0"?>
<model>
<name>x500_lidar_front</name>
<version>1.0</version>
<sdf version="1.9">model.sdf</sdf>
<author>
<name>Claudio Chies</name>
<email>[email protected]</email>
</author>
<description>An x500 a lidar pointing to the front for collision prevention</description>
</model>
62 changes: 62 additions & 0 deletions models/x500_lidar_front/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version='1.9'>
<model name='x500_lidar_front'>
<include merge='true'>
<uri>x500</uri>
</include>
<include merge='true'>
<uri>model://LW20</uri>
<pose relative_to="base_link">.15 0 .01 0 0 0</pose>
</include>
<joint name="lidar_model_joint" type="fixed">
<parent>base_link</parent>
<child>lw20_link</child>
<pose relative_to="base_link">-0 0 0 0 0 0</pose>
</joint>
<link name="lidar_sensor_link">
<pose relative_to="base_link">0.3 0 0.01 0 0 0</pose>
<inertial>
<mass>0.001</mass>
<inertia>
<ixx>0.00001</ixx>
<iyy>0.00001</iyy>
<izz>0.00001</izz>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
</inertia>
</inertial>
<sensor name='lidar' type='gpu_lidar'>"
<pose relative_to="base_link">.15 0 .01 1.57 0 0</pose>
<update_rate>50</update_rate>
<ray>
<scan>
<horizontal>
<samples>1</samples>
<resolution>1</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</horizontal>
<vertical>
<samples>1</samples>
<resolution>1</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</vertical>
</scan>
<range>
<min>0.1</min>
<max>100.0</max>
<resolution>0.01</resolution>
</range>
</ray>
<always_on>1</always_on>
<visualize>true</visualize>
</sensor>
</link>
<joint name="lidar_sensor_joint" type="fixed">
<parent>base_link</parent>
<child>lidar_sensor_link</child>
</joint>
</model>
</sdf>

0 comments on commit 9e47793

Please sign in to comment.