1+ <?xml version =' 1.0' encoding =' utf-8' ?>
2+ <!--
3+ SPDX-FileCopyrightText: Alliander N. V.
4+
5+ SPDX-License-Identifier: Apache-2.0
6+ -->
7+
8+ <!--
9+ Based on:
10+ 1.https://bitbucket.org/DataspeedInc/velodyne_simulator/src/master/velodyne_description/urdf/VLP-16.urdf.xacro
11+ 2.https://github.com/husarion/ros_components_description/blob/ros2/urdf/velodyne_puck.urdf.xacro
12+ -->
13+
14+ <robot xmlns : xacro =" http://www.ros.org/wiki/xacro" name =" VLP-16" >
15+ <xacro : property name =" M_PI" value =" 3.1415926535897931" />
16+ <xacro : macro name =" VLP-16"
17+ params ="
18+ *origin
19+ parent:=cover_link
20+ name:=velodyne
21+ topic:=/velodyne_points
22+ update_rate:=10
23+ lasers:=16
24+ samples:=1875
25+ min_range:=0.3
26+ max_range:=130.0
27+ min_angle:=-${M_PI}
28+ max_angle:=${M_PI}
29+ " >
30+
31+ <joint name =" ${name}_base_mount_joint" type =" fixed" >
32+ <xacro : insert_block name =" origin" />
33+ <parent link =" ${parent}" />
34+ <child link =" ${name}_base_link" />
35+ </joint >
36+
37+ <link name =" ${name}_base_link" >
38+ <inertial >
39+ <mass value =" 0.83" />
40+ <origin xyz =" 0 0 0.03585" />
41+ <inertia ixx =" ${(0.83 * (3.0*0.0516*0.0516 + 0.0717*0.0717)) / 12.0}" ixy =" 0" ixz =" 0"
42+ iyy =" ${(0.83 * (3.0*0.0516*0.0516 + 0.0717*0.0717)) / 12.0}" iyz =" 0"
43+ izz =" ${0.5 * 0.83 * (0.0516*0.0516)}" />
44+ </inertial >
45+ <visual >
46+ <geometry >
47+ <mesh filename =" package://velodyne_description/meshes/VLP16_base_1.dae" />
48+ </geometry >
49+ </visual >
50+ <visual >
51+ <geometry >
52+ <mesh filename =" package://velodyne_description/meshes/VLP16_base_2.dae" />
53+ </geometry >
54+ </visual >
55+ <collision >
56+ <origin rpy =" 0 0 0" xyz =" 0 0 0.03585" />
57+ <geometry >
58+ <cylinder radius =" 0.0516" length =" 0.0717" />
59+ </geometry >
60+ </collision >
61+ </link >
62+
63+ <joint name =" ${name}_base_scan_joint" type =" fixed" >
64+ <origin xyz =" 0 0 0.0377" rpy =" 0 0 0" />
65+ <parent link =" ${name}_base_link" />
66+ <child link =" ${name}_lidar" />
67+ </joint >
68+
69+ <link name =" ${name}_lidar" >
70+ <inertial >
71+ <mass value =" 0.01" />
72+ <origin xyz =" 0 0 0" />
73+ <inertia ixx =" 1e-7" ixy =" 0" ixz =" 0" iyy =" 1e-7" iyz =" 0" izz =" 1e-7" />
74+ </inertial >
75+ <visual >
76+ <origin xyz =" 0 0 -0.0377" />
77+ <geometry >
78+ <mesh filename =" package://velodyne_description/meshes/VLP16_scan.dae" />
79+ </geometry >
80+ </visual >
81+ </link >
82+
83+ <gazebo reference =" ${name}_lidar" >
84+ <sensor type =" gpu_lidar" name =" ${name}" >
85+ <always_on >true</always_on >
86+ <update_rate >${update_rate}</update_rate >
87+
88+ <topic >${topic}</topic >
89+ <visualize >false</visualize >
90+
91+ <ignition_frame_id >${name}_lidar</ignition_frame_id >
92+ <frame_id >${name}_lidar</frame_id >
93+
94+ <ray >
95+ <scan >
96+ <horizontal >
97+ <samples >${samples}</samples >
98+ <resolution >1</resolution >
99+ <min_angle >${min_angle}</min_angle >
100+ <max_angle >${max_angle}</max_angle >
101+ </horizontal >
102+ <vertical >
103+ <samples >${lasers}</samples >
104+ <resolution >1</resolution >
105+ <min_angle >-${15.0*M_PI/180.0}</min_angle >
106+ <max_angle > ${15.0*M_PI/180.0}</max_angle >
107+ </vertical >
108+ </scan >
109+ <range >
110+ <min >${min_range}</min >
111+ <max >${max_range}</max >
112+ <resolution >0.001</resolution >
113+ </range >
114+ <noise >
115+ <type >gaussian</type >
116+ <mean >0.0</mean >
117+ <stddev >0.0</stddev >
118+ </noise >
119+ </ray >
120+ </sensor >
121+ </gazebo >
122+
123+ </xacro : macro >
124+ </robot >
0 commit comments