init
This commit is contained in:
199
velodyne_hdl32/meshes/velodyne_base.dae
Normal file
199
velodyne_hdl32/meshes/velodyne_base.dae
Normal file
File diff suppressed because one or more lines are too long
199
velodyne_hdl32/meshes/velodyne_top.dae
Normal file
199
velodyne_hdl32/meshes/velodyne_top.dae
Normal file
File diff suppressed because one or more lines are too long
17
velodyne_hdl32/model.config
Normal file
17
velodyne_hdl32/model.config
Normal file
@@ -0,0 +1,17 @@
|
||||
<?xml version="1.0"?>
|
||||
|
||||
<model>
|
||||
<name>Velodyne HDL-32</name>
|
||||
<version>1.0</version>
|
||||
<sdf version="1.5">model.sdf</sdf>
|
||||
|
||||
<author>
|
||||
<name>Nate Koenig</name>
|
||||
<email>nate@osrfoundation.org</email>
|
||||
</author>
|
||||
|
||||
<description>
|
||||
A model of a Velodyne HDL-32 LiDAR sensor.
|
||||
</description>
|
||||
|
||||
</model>
|
108
velodyne_hdl32/model.sdf
Normal file
108
velodyne_hdl32/model.sdf
Normal file
@@ -0,0 +1,108 @@
|
||||
<?xml version="1.0" ?>
|
||||
<sdf version="1.5">
|
||||
<model name="velodyne">
|
||||
<link name="base">
|
||||
<pose>0 0 0.029335 0 0 0</pose>
|
||||
<inertial>
|
||||
<mass>1.2</mass>
|
||||
<inertia>
|
||||
<ixx>0.001087473</ixx>
|
||||
<iyy>0.001087473</iyy>
|
||||
<izz>0.001092437</izz>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyz>0</iyz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name="base_collision">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>.04267</radius>
|
||||
<length>.05867</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="base_visual">
|
||||
<pose>0 0 -0.029335 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://velodyne_hdl32/meshes/velodyne_base.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<link name="top">
|
||||
<pose>0 0 0.095455 0 0 0</pose>
|
||||
<inertial>
|
||||
<mass>0.1</mass>
|
||||
<inertia>
|
||||
<ixx>0.000090623</ixx>
|
||||
<iyy>0.000090623</iyy>
|
||||
<izz>0.000091036</izz>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyz>0</iyz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name="top_collision">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.04267</radius>
|
||||
<length>0.07357</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="top_visual">
|
||||
<pose>0 0 -0.0376785 0 0 1.5707</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://velodyne_hdl32/meshes/velodyne_top.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
<sensor type="ray" name="sensor">
|
||||
<pose>0 0 -0.004645 1.5707 0 0</pose>
|
||||
<visualize>true</visualize>
|
||||
<update_rate>30</update_rate>
|
||||
<ray>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<mean>0.0</mean>
|
||||
<stddev>0.1</stddev>
|
||||
</noise>
|
||||
|
||||
<scan>
|
||||
<horizontal>
|
||||
<samples>32</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>-0.53529248</min_angle>
|
||||
<max_angle>0.18622663</max_angle>
|
||||
</horizontal>
|
||||
</scan>
|
||||
|
||||
<range>
|
||||
<min>0.1</min>
|
||||
<max>70</max>
|
||||
<resolution>0.02</resolution>
|
||||
</range>
|
||||
</ray>
|
||||
</sensor>
|
||||
</link>
|
||||
|
||||
<joint type="revolute" name="joint">
|
||||
<pose>0 0 -0.036785 0 0 0</pose>
|
||||
<parent>base</parent>
|
||||
<child>top</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-10000000000000000</lower>
|
||||
<upper>10000000000000000</upper>
|
||||
</limit>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
</model>
|
||||
</sdf>
|
Reference in New Issue
Block a user