Skip to content

Commit

Permalink
added x500 model with frontfacing and downfacing lidar
Browse files Browse the repository at this point in the history
added x500 model with frontfacing and downfacing lidar
  • Loading branch information
dirksavage88 authored and Claudio-Chies committed Nov 1, 2024
1 parent 536305a commit 308dd27
Show file tree
Hide file tree
Showing 6 changed files with 147 additions and 29 deletions.
11 changes: 0 additions & 11 deletions models/x500_lidar/model.config

This file was deleted.

18 changes: 0 additions & 18 deletions models/x500_lidar/model.sdf

This file was deleted.

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://Broadcom-rangefinder</uri>
<pose>0.12 0 .2 0 0 0</pose>
</include>
<joint name="lidar_model_joint" type="fixed">
<parent>base_link</parent>
<child>lidar_model_link</child>
<pose relative_to="base_link">-.1 0 .26 -1.57 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://Broadcom-rangefinder</uri>
<pose>0.12 0 .2 0 0 0</pose>
</include>
<joint name="lidar_model_joint" type="fixed">
<parent>base_link</parent>
<child>lidar_model_link</child>
<pose relative_to="base_link">-.1 0 .26 -1.57 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>0 0 0 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 308dd27

Please sign in to comment.