Skip to content

Commit

Permalink
new lidar_v2 model and x500_lidar vehicle
Browse files Browse the repository at this point in the history
  • Loading branch information
dakejahl authored May 29, 2024
1 parent d754381 commit 881558c
Show file tree
Hide file tree
Showing 11 changed files with 10,753 additions and 0 deletions.
10,630 changes: 10,630 additions & 0 deletions models/lidar_2d_v2/meshes/lidar_2d_v2.dae

Large diffs are not rendered by default.

Binary file added models/lidar_2d_v2/meshes/lidar_2d_v2.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
15 changes: 15 additions & 0 deletions models/lidar_2d_v2/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
<?xml version="1.0"?>

<model>
<name>Lidar 2d v2</name>
<version>1.0</version>
<sdf version="1.6">model.sdf</sdf>

<author>
<name>Cole Biesemeyer</name>
</author>

<description>
A generic planar lidar.
</description>
</model>
79 changes: 79 additions & 0 deletions models/lidar_2d_v2/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<model name="lidar_2d_v2">
<link name="link">
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0.0435 0 0 0</pose>
<mass>0.37</mass>
<inertia>
<ixx>0.00034437749999999994</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00034437749999999994</iyy>
<iyz>0</iyz>
<izz>0.00022199999999999998</izz>
</inertia>
</inertial>
<collision name="collision_base">
<pose>0 0 0.0205 0 0 0</pose>
<geometry>
<box>
<size>0.06 0.06 0.041</size>
</box>
</geometry>
</collision>
<collision name="collision_mid">
<pose>0 0 0.055 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.025</radius>
<length>0.028</length>
</cylinder>
</geometry>
</collision>
<collision name="collision_top">
<pose>0 0 0.078 0 0 0</pose>
<geometry>
<box>
<size>0.056 0.056 0.018</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://lidar_2d_v2/meshes/lidar_2d_v2.dae</uri>
</mesh>
</geometry>
</visual>
<sensor name="lidar_2d_v2" type="gpu_ray">
<pose>0 0 0.055 0 0 0</pose>
<ray>
<scan>
<horizontal>
<samples>1080</samples>
<resolution>1</resolution>
<min_angle>-2.356195</min_angle>
<max_angle>2.356195</max_angle>
</horizontal>
</scan>
<range>
<min>0.1</min>
<max>30</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.001</stddev>
</noise>
</ray>
<always_on>0</always_on>
<update_rate>30</update_rate>
<visualize>false</visualize>
</sensor>

</link>
</model>
</sdf>
Binary file added models/lidar_2d_v2/thumbnails/1.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added models/lidar_2d_v2/thumbnails/2.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added models/lidar_2d_v2/thumbnails/3.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added models/lidar_2d_v2/thumbnails/4.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added models/lidar_2d_v2/thumbnails/5.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
11 changes: 11 additions & 0 deletions models/x500_lidar/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
<?xml version="1.0"?>
<model>
<name>x500-lidar</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/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'>
<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 881558c

Please sign in to comment.