|
231 | 231 | <always_on>1</always_on> |
232 | 232 | <update_rate>400</update_rate> |
233 | 233 | <imu> |
234 | | - <angular_velocity> |
235 | | - <x> |
236 | | - <noise type="gaussian"> |
237 | | - <mean>0</mean> |
238 | | - <stddev>2e-4</stddev> |
239 | | - <bias_mean>0.0000075</bias_mean> |
240 | | - <bias_stddev>0.0000008</bias_stddev> |
241 | | - <dynamic_bias_stddev>0.0000004</dynamic_bias_stddev> |
242 | | - <dynamic_bias_correlation_time>1000.0</dynamic_bias_correlation_time> |
243 | | - </noise> |
244 | | - </x> |
245 | | - <y> |
246 | | - <noise type="gaussian"> |
247 | | - <mean>0</mean> |
248 | | - <stddev>2e-4</stddev> |
249 | | - <bias_mean>0.0000075</bias_mean> |
250 | | - <bias_stddev>0.0000008</bias_stddev> |
251 | | - <dynamic_bias_stddev>0.0000004</dynamic_bias_stddev> |
252 | | - <dynamic_bias_correlation_time>1000.0</dynamic_bias_correlation_time> |
253 | | - </noise> |
254 | | - </y> |
255 | | - <z> |
256 | | - <noise type="gaussian"> |
257 | | - <mean>0</mean> |
258 | | - <stddev>2e-4</stddev> |
259 | | - <bias_mean>0.0000075</bias_mean> |
260 | | - <bias_stddev>0.0000008</bias_stddev> |
261 | | - <dynamic_bias_stddev>0.0000004</dynamic_bias_stddev> |
262 | | - <dynamic_bias_correlation_time>1000.0</dynamic_bias_correlation_time> |
263 | | - </noise> |
264 | | - </z> |
265 | | - </angular_velocity> |
266 | | - <linear_acceleration> |
267 | | - <x> |
268 | | - <noise type="gaussian"> |
269 | | - <mean>0</mean> |
270 | | - <stddev>1e-2</stddev> |
271 | | - <bias_mean>0.1</bias_mean> |
272 | | - <bias_stddev>0.001</bias_stddev> |
273 | | - <dynamic_bias_stddev>0.002</dynamic_bias_stddev> |
274 | | - <dynamic_bias_correlation_time>300.0</dynamic_bias_correlation_time> |
275 | | - </noise> |
276 | | - </x> |
277 | | - <y> |
278 | | - <noise type="gaussian"> |
279 | | - <mean>0</mean> |
280 | | - <stddev>1e-2</stddev> |
281 | | - <bias_mean>0.1</bias_mean> |
282 | | - <bias_stddev>0.001</bias_stddev> |
283 | | - <dynamic_bias_stddev>0.002</dynamic_bias_stddev> |
284 | | - <dynamic_bias_correlation_time>300.0</dynamic_bias_correlation_time> |
285 | | - </noise> |
286 | | - </y> |
287 | | - <z> |
288 | | - <noise type="gaussian"> |
289 | | - <mean>0</mean> |
290 | | - <stddev>1e-2</stddev> |
291 | | - <bias_mean>0.1</bias_mean> |
292 | | - <bias_stddev>0.001</bias_stddev> |
293 | | - <dynamic_bias_stddev>0.002</dynamic_bias_stddev> |
294 | | - <dynamic_bias_correlation_time>300.0</dynamic_bias_correlation_time> |
295 | | - </noise> |
296 | | - </z> |
297 | | - </linear_acceleration> |
298 | | - </imu> |
| 234 | + <angular_velocity> |
| 235 | + <x> |
| 236 | + <noise type="gaussian"> |
| 237 | + <mean>0</mean> |
| 238 | + <stddev>0.009</stddev> |
| 239 | + <bias_mean>0.00075</bias_mean> |
| 240 | + <bias_stddev>0.005</bias_stddev> |
| 241 | + <dynamic_bias_stddev>0.00002</dynamic_bias_stddev> |
| 242 | + <dynamic_bias_correlation_time>400.0</dynamic_bias_correlation_time> |
| 243 | + <precision>0.00025</precision> |
| 244 | + </noise> |
| 245 | + </x> |
| 246 | + <y> |
| 247 | + <noise type="gaussian"> |
| 248 | + <mean>0</mean> |
| 249 | + <stddev>0.009</stddev> |
| 250 | + <bias_mean>0.00075</bias_mean> |
| 251 | + <bias_stddev>0.005</bias_stddev> |
| 252 | + <dynamic_bias_stddev>0.00002</dynamic_bias_stddev> |
| 253 | + <dynamic_bias_correlation_time>400.0</dynamic_bias_correlation_time> |
| 254 | + <precision>0.00025</precision> |
| 255 | + </noise> |
| 256 | + </y> |
| 257 | + <z> |
| 258 | + <noise type="gaussian"> |
| 259 | + <mean>0</mean> |
| 260 | + <stddev>0.009</stddev> |
| 261 | + <bias_mean>0.00075</bias_mean> |
| 262 | + <bias_stddev>0.005</bias_stddev> |
| 263 | + <dynamic_bias_stddev>0.00002</dynamic_bias_stddev> |
| 264 | + <dynamic_bias_correlation_time>400.0</dynamic_bias_correlation_time> |
| 265 | + <precision>0.00025</precision> |
| 266 | + </noise> |
| 267 | + </z> |
| 268 | + </angular_velocity> |
| 269 | + <linear_acceleration> |
| 270 | + <x> |
| 271 | + <noise type="gaussian"> |
| 272 | + <mean>0</mean> |
| 273 | + <stddev>0.021</stddev> |
| 274 | + <bias_mean>0.05</bias_mean> |
| 275 | + <bias_stddev>0.0075</bias_stddev> |
| 276 | + <dynamic_bias_stddev>0.000375</dynamic_bias_stddev> |
| 277 | + <dynamic_bias_correlation_time>175.0</dynamic_bias_correlation_time> |
| 278 | + <precision>0.005</precision> |
| 279 | + </noise> |
| 280 | + </x> |
| 281 | + <y> |
| 282 | + <noise type="gaussian"> |
| 283 | + <mean>0</mean> |
| 284 | + <stddev>0.021</stddev> |
| 285 | + <bias_mean>0.05</bias_mean> |
| 286 | + <bias_stddev>0.0075</bias_stddev> |
| 287 | + <dynamic_bias_stddev>0.000375</dynamic_bias_stddev> |
| 288 | + <dynamic_bias_correlation_time>175.0</dynamic_bias_correlation_time> |
| 289 | + <precision>0.005</precision> |
| 290 | + </noise> |
| 291 | + </y> |
| 292 | + <z> |
| 293 | + <noise type="gaussian"> |
| 294 | + <mean>0</mean> |
| 295 | + <stddev>0.021</stddev> |
| 296 | + <bias_mean>0.05</bias_mean> |
| 297 | + <bias_stddev>0.0075</bias_stddev> |
| 298 | + <dynamic_bias_stddev>0.000375</dynamic_bias_stddev> |
| 299 | + <dynamic_bias_correlation_time>175.0</dynamic_bias_correlation_time> |
| 300 | + <precision>0.005</precision> |
| 301 | + </noise> |
| 302 | + </z> |
| 303 | + </linear_acceleration> |
| 304 | + </imu> |
299 | 305 | </sensor> |
300 | 306 |
|
301 | 307 | <sensor name="front_laser" type="gpu_lidar"> |
|
0 commit comments