-
Notifications
You must be signed in to change notification settings - Fork 3
/
Copy pathtg30_f120a.gazebo
79 lines (75 loc) · 2.45 KB
/
tg30_f120a.gazebo
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
<?xml version="1.0"?>
<robot name="lrf_tg30_f120a" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- set to "true" to visualize the LRF laser on Gazebo -->
<xacro:arg name="front_laser_visual" default="false" />
<xacro:arg name="back_laser_visual" default="false" />
<xacro:property name="lrf_color" value="Gazebo/FlatBlack" />
<!-- LRF: TG30 -->
<!-- DATA: http://www.ydlidar.com/Public/upload/files/2022-06-21/YDLIDAR%20TG30%20Data%20Sheet%20V1.4(211230).pdf -->
<gazebo reference="front_lrf_link">
<material>${lrf_color}</material>
<selfCollide>true</selfCollide>
<sensor type="ray" name="tg30_lidar_front">
<pose>0 0 0 0 0 0</pose>
<visualize>$(arg front_laser_visual)</visualize>
<update_rate>12</update_rate>
<ray>
<scan>
<horizontal>
<samples>1636</samples>
<resolution>0.22</resolution>
<min_angle>0.0</min_angle>
<max_angle>6.28319</max_angle>
</horizontal>
</scan>
<range>
<min>0.05</min>
<max>30.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_tg30_lidar_front_controller" filename="libgazebo_ros_laser.so">
<topicName>scan</topicName>
<frameName>front_lrf_link</frameName>
</plugin>
</sensor>
</gazebo>
<gazebo reference="back_lrf_link">
<material>${lrf_color}</material>
<selfCollide>true</selfCollide>
<sensor type="ray" name="tg30_lidar_back">
<pose>0 0 0 0 0 0</pose>
<visualize>$(arg back_laser_visual)</visualize>
<update_rate>12</update_rate>
<ray>
<scan>
<horizontal>
<samples>1636</samples>
<resolution>0.22</resolution>
<min_angle>0.0</min_angle>
<max_angle>6.28319</max_angle>
</horizontal>
</scan>
<range>
<min>0.05</min>
<max>30.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_tg30_lidar_back_controller" filename="libgazebo_ros_laser.so">
<topicName>scan</topicName>
<frameName>back_lrf_link</frameName>
</plugin>
</sensor>
</gazebo>
</robot>