forked from RobotnikAutomation/guardian_sim
-
Notifications
You must be signed in to change notification settings - Fork 0
/
guardian.gazebo
189 lines (170 loc) · 5.58 KB
/
guardian.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
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
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
<?xml version="1.0"?>
<robot>
<!-- ros_control plugin -->
<gazebo>
<plugin name="ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/guardian</robotNamespace>
<controlPeriod>0.001</controlPeriod>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
</plugin>
</gazebo>
<gazebo>
<plugin name="skid_steer_drive_controller" filename="libgazebo_ros_skid_steer_drive.so">
<updateRate>100.0</updateRate>
<robotNamespace>/guardian</robotNamespace>
<leftFrontJoint>joint_front_left_wheel</leftFrontJoint>
<rightFrontJoint>joint_front_right_wheel</rightFrontJoint>
<leftRearJoint>joint_back_left_wheel</leftRearJoint>
<rightRearJoint>joint_back_right_wheel</rightRearJoint>
<wheelSeparation>0.6</wheelSeparation>
<wheelDiameter>0.300</wheelDiameter>
<robotBaseFrame>base_link</robotBaseFrame>
<torque>20</torque>
<topicName>/guardian/cmd_vel</topicName>
<commandTopic>/guardian/cmd_vel</commandTopic>
<odometryTopic>/guardian/odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
<!-- broadcastTF>false</broadcastTF -->
</plugin>
</gazebo>
<gazebo reference="base_footprint">
<material>Gazebo/Green</material>
</gazebo>
<gazebo reference="base_link">
<material>Gazebo/Red</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<gazebo reference="back_left_wheel">
<mu1 value="2.5"/>
<mu2 value="0.9"/>
<fdir1 value="1 0 0"/>
<!-- kp>100000000.0</kp>
<kd>100.0</kd-->
<kp>10000.0</kp>
<kd>100.0</kd>
<maxVel>2.0</maxVel>
<material>Gazebo/Grey</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<gazebo reference="back_right_wheel">
<mu1 value="2.5"/>
<mu2 value="0.9"/>
<fdir1 value="1 0 0"/>
<maxVel>2.0</maxVel>
<kp>10000.0</kp>
<kd>100.0</kd>
<material>Gazebo/Grey</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<gazebo reference="front_left_wheel">
<mu1 value="2.5"/>
<mu2 value="0.9"/>
<fdir1 value="1 0 0"/>
<maxVel>2.0</maxVel>
<kp>10000.0</kp>
<kd>100.0</kd>
<material>Gazebo/Grey</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<gazebo reference="front_right_wheel">
<mu1 value="2.5"/>
<mu2 value="0.9"/>
<fdir1 value="1 0 0"/>
<maxVel>2.0</maxVel>
<kp>10000.0</kp>
<kd>100.0</kd>
<material>Gazebo/Grey</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<!-- camera -->
<!-- gazebo reference="camera_link" -->
<gazebo reference="camera_tilt_link">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material>Gazebo/Red</material>
<sensor type="camera" name="camera1">
<update_rate>30.0</update_rate>
<camera name="head">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>800</width>
<height>800</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame.
That pixel's noise value is added to each of its color
channels, which at that point lie in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>/guardian/camera1</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_tilt_link</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</gazebo>
<!-- hokuyo -->
<gazebo reference="hokuyo_laser_link">
<!-- sensor type="gpu_ray" name="head_hokuyo_sensor" -->
<sensor type="ray" name="head_hokuyo_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>30</update_rate>
<ray>
<scan>
<horizontal>
<!-- samples>720</samples>
<resolution>1</resolution>
<min_angle>-1.570796</min_angle>
<max_angle>1.570796</max_angle -->
<samples>1081</samples>
<resolution>1</resolution>
<min_angle>2.35619449</min_angle> <!-- +/-135 deg -->
<max_angle>-2.35619449</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</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_head_hokuyo_controller" filename="libgazebo_ros_gpu_laser.so" -->
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
<topicName>/guardian/laser_tilt_front</topicName>
<frameName>hokuyo_laser_link</frameName>
</plugin>
</sensor>
</gazebo>
<gazebo>
<plugin name="ros_imu" filename="libgazebo_ros_imu.so">
<robotNamespace>/guardian</robotNamespace>
<topicName>imu_data</topicName>
<bodyName>imu_link </bodyName>
<serviceName>/imu_service</serviceName>
<gaussianNoise>0.005</gaussianNoise>
</plugin>
</gazebo>
</robot>