Skip to content

Commit 3138574

Browse files
authored
include lslidar_m10_p
1 parent 3cd84c0 commit 3138574

File tree

1 file changed

+53
-0
lines changed

1 file changed

+53
-0
lines changed

urdf/lidar_m10_p.urdf.xacro

Lines changed: 53 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,53 @@
1+
<?xml version="1.0"?>
2+
<robot xmlns:xacro="http://wiki.ros.org/xacro">
3+
4+
<xacro:macro name="sensor_lidar_m10_p" params="prefix parent prefix_topic:='front_laser' *origin min_angle:=3.14159 max_angle:=-3.14159 gpu:=^|false">
5+
6+
<joint name="${prefix}_base_joint" type="fixed">
7+
<xacro:insert_block name="origin" />
8+
<parent link="${parent}"/>
9+
<child link="${prefix}_base_link"/>
10+
</joint>
11+
12+
13+
<link name="${prefix}_base_link">
14+
<collision>
15+
<origin xyz="0 0 0" rpy="0 0 0"/>
16+
<geometry>
17+
<mesh filename="package://robotnik_sensors/meshes/lidar_m10_p.dae"/>
18+
</geometry>
19+
</collision>
20+
21+
<visual>
22+
<origin xyz="0 0 0" rpy="0 0 0"/>
23+
<geometry>
24+
<mesh filename="package://robotnik_sensors/meshes/lidar_m10_p.dae" scale="0.001 0.001 0.001"/>
25+
</geometry>
26+
</visual>
27+
28+
<inertial>
29+
<mass value="0.190" />
30+
<origin xyz="0.01 0 0.028" rpy="0 0 0"/>
31+
<xacro:solid_cuboid_inertia m="0.190" w="0.09674" h="0.056" d="0.056" />
32+
</inertial>
33+
</link>
34+
35+
<joint name="${prefix}_joint" type="fixed">
36+
<origin xyz="0 0 0.0461" rpy="0 0 0"/>
37+
<parent link="${prefix}_base_link"/>
38+
<child link="${prefix}_link"/>
39+
</joint>
40+
41+
42+
<link name="${prefix}_link">
43+
</link>
44+
45+
46+
47+
48+
</xacro:macro>
49+
50+
51+
52+
53+
</robot>

0 commit comments

Comments
 (0)