forked from eborghi10/create_autonomy
-
-
Notifications
You must be signed in to change notification settings - Fork 38
/
Copy pathrplidar.xacro
86 lines (74 loc) · 2.45 KB
/
rplidar.xacro
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:property name="name" value="rplidar"/>
<xacro:property name="parent" value="base_link"/>
<xacro:property name="parent_link" value="${parent}"/>
<xacro:property name="link_name" value="${name}_link"/>
<xacro:property name="laser_link" value="laser_link"/>
<xacro:property name="rate_hz" value="10"/>
<xacro:property name="min_range_cm" value="15"/>
<xacro:property name="max_range_m" value="12.0"/>
<xacro:property name="samples" value="1000"/>
<xacro:property name="resolution_mm" value="0.5"/>
<xacro:property name="min_angle_rad" value="${-pi}"/>
<xacro:property name="max_angle_rad" value="${pi}"/>
<xacro:property name="topic_name" value="${name}/scan"/>
<!-- Set GPU values -->
<xacro:if value="$(arg use_gpu)">
<xacro:property name="gpu" value="gpu_"/>
</xacro:if>
<xacro:unless value="$(arg use_gpu)">
<xacro:property name="gpu" value=""/>
</xacro:unless>
<joint name="${name}_joint" type="fixed">
<origin xyz="${laser_origin}"/>
<parent link="${parent_link}"/>
<child link="${link_name}"/>
</joint>
<link name="${link_name}">
<visual>
<geometry>
<mesh filename="package://ca_description/meshes/sensors/rplidar.dae"/>
</geometry>
</visual>
</link>
<joint name="laser_joint" type="fixed">
<origin xyz="0 0 0.0308"/>
<parent link="${link_name}"/>
<child link="${laser_link}"/>
</joint>
<link name="${laser_link}"/>
<gazebo reference="${link_name}">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="${laser_link}">
<sensor type="${gpu}ray" name="${name}_sensor">
<visualize>$(arg visualize)</visualize>
<update_rate>${rate_hz}</update_rate>
<ray>
<scan>
<horizontal>
<samples>${samples}</samples>
<resolution>10</resolution>
<min_angle>${min_angle_rad}</min_angle>
<max_angle>${max_angle_rad}</max_angle>
</horizontal>
</scan>
<range>
<min>${min_range_cm*cm_to_meters}</min>
<max>${max_range_m}</max>
<resolution>${resolution_mm*mm_to_meters}</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_${name}" filename="libgazebo_ros_${gpu}laser.so">
<topicName>${topic_name}</topicName>
<frameName>${laser_link}</frameName>
</plugin>
</sensor>
</gazebo>
</robot>