-
Notifications
You must be signed in to change notification settings - Fork 0
/
gazebo.xacro
170 lines (161 loc) · 6.5 KB
/
gazebo.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
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
<?xml version="1.0" ?>
<robot name="zinger" xmlns:xacro="http://www.ros.org/wiki/xacro" >
<!--
GAZEBO MACROS
-->
<!--
Define Gazebo specific macro's here because this file isn't included if we're not running
Gazebo
-->
<xacro:macro name="gazebo_reference_link_wheel" params="name">
<gazebo reference="link_wheel_${name}">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<kp>500000.0</kp>
<kd>10.0</kd>
<minDepth>0.001</minDepth>
<maxVel>0.1</maxVel>
<fdir1>1 0 0</fdir1>
<selfCollide>true</selfCollide>
</gazebo>
</xacro:macro>
<!-- Sensors -->
<xacro:macro name="gazebo_sensor_imu" params="name update_rate:=25" >
<gazebo reference="link_sensor_imu_${name}">
<sensor name="${name}" type="imu">
<ignition_frame_id>link_sensor_imu_${name}</ignition_frame_id>
<always_on>true</always_on>
<update_rate>${update_rate}</update_rate>
<imu>
<angular_velocity>
<x>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
</z>
</angular_velocity>
<linear_acceleration>
<x>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
</z>
</linear_acceleration>
</imu>
<plugin
filename="libignition-gazebo-imu-system.so"
name="ignition::gazebo::systems::Imu">
<alwaysOn>true</alwaysOn>
<updateRate>25</updateRate>
<topic>imu</topic>
<imuName>imu_center</imuName>
</plugin>
</sensor>
</gazebo>
<gazebo reference="joint_body_to_sensor_imu_${name}">
<preserveFixedJoint>true</preserveFixedJoint>
</gazebo>
</xacro:macro>
<xacro:macro name="gazebo_sensor_rplidar" params="name" >
<gazebo reference="link_sensor_lidar_${name}">
<sensor name="${name}" type="gpu_lidar">
<!--
Move the sensor up slightly from the bottom of the lidar unit.
-->
<pose>0 0 0.02 0 0 0</pose>
<alwaysOn>true</alwaysOn>
<topic>rplidar_front/scan</topic>
<update_rate>25</update_rate>
<lidarName>rplidar_front</lidarName>
<visualize>true</visualize>
<ignition_frame_id>link_sensor_lidar_${name}</ignition_frame_id>
<ray>
<scan>
<horizontal>
<samples>640</samples>
<resolution>1.0</resolution>
<min_angle>${-pi}</min_angle>
<max_angle>${pi}</max_angle>
</horizontal>
<vertical>
<samples>1</samples>
<resolution>1</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</vertical>
</scan>
<range>
<min>0.164</min>
<max>12.0</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin
filename="libignition-gazebo-sensors-system.so"
name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
</sensor>
</gazebo>
<gazebo reference="joint_body_to_sensor_lidar_${name}">
<preserveFixedJoint>true</preserveFixedJoint>
</gazebo>
</xacro:macro>
<!--
GAZEBO
-->
<xacro:gazebo_reference_link_wheel name="left_front" />
<xacro:gazebo_reference_link_wheel name="left_rear" />
<xacro:gazebo_reference_link_wheel name="right_rear" />
<xacro:gazebo_reference_link_wheel name="right_front" />
<xacro:gazebo_sensor_imu name="imu_center" />
<xacro:gazebo_sensor_rplidar name="rplidar_front" />
<gazebo>
<plugin
filename="ign_ros2_control-system"
name="ign_ros2_control::IgnitionROS2ControlPlugin">
<parameters>$(find zinger_description)/config/zinger.yaml</parameters>
</plugin>
</gazebo>
<gazebo>
<plugin
filename="libignition-gazebo-pose-publisher-system.so"
name="ignition::gazebo::systems::PosePublisher">
<publish_link_pose>true</publish_link_pose>
<publish_sensor_pose>true</publish_sensor_pose>
<publish_collision_pose>false</publish_collision_pose>
<publish_visual_pose>false</publish_visual_pose>
<publish_model_pose>true</publish_model_pose>
<publish_nested_model_pose>true</publish_nested_model_pose>
<use_pose_vector_msg>true</use_pose_vector_msg>
<static_publisher>true</static_publisher>
<static_update_frequency>-1</static_update_frequency>
</plugin>
</gazebo>
</robot>