forked from wilselby/ouster_example
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathoutput.urdf
122 lines (121 loc) · 4.03 KB
/
output.urdf
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
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from ouster_description/urdf/example.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="os1_example">
<!-- Base Footprint -->
<link name="base_footprint"/>
<!-- Base Link -->
<joint name="footprint" type="fixed">
<parent link="base_footprint"/>
<child link="base_link"/>
<origin rpy="0 0 0" xyz="0 0 0.00"/>
</joint>
<link name="base_link">
<visual>
<geometry>
<box size="0.3 0.3 0.03"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.3 0.3 0.03"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0"/>
<mass value="10"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<joint name="os1_sensor_mount_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<parent link="base_link"/>
<child link="os1_sensor"/>
</joint>
<link name="os1_sensor">
<inertial>
<mass value="0.33"/>
<origin rpy="0 0 0" xyz="0 0 0.05"/>
<inertia ixx="0.000241148" ixy="0" ixz="0" iyy="0.000241148" iyz="0" izz="0.000264"/>
</inertial>
<collision name="base_collision">
<origin rpy="0 0 0" xyz="0 0 0.05"/>
<geometry>
<cylinder length="0.073" radius="0.04"/>
</geometry>
</collision>
<visual name="base_visual">
<origin rpy="0 0 1.5707" xyz="0 0 0.05"/>
<geometry>
<mesh filename="package://ouster_description/meshes/os1_64.dae"/>
</geometry>
</visual>
</link>
<link name="os1_imu"/>
<link name="os1_lidar"/>
<joint name="os1_sensor_imu_link_joint" type="fixed">
<parent link="os1_sensor"/>
<child link="os1_imu"/>
<origin rpy="0 0 0" xyz="0.006253 -0.011775 0.007645"/>
</joint>
<gazebo reference="os1_imu">
</gazebo>
<joint name="os1_sensor_lidar_link_joint" type="fixed">
<parent link="os1_sensor"/>
<child link="os1_lidar"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.03618"/>
</joint>
<!-- Gazebo requires the ouster_gazebo_plugins package -->
<gazebo reference="os1_sensor">
<sensor name="os1_sensor-OS1-64" type="ray">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>10</update_rate>
<ray>
<scan>
<horizontal>
<samples>220</samples>
<resolution>1</resolution>
<min_angle>-3.141592653589793</min_angle>
<max_angle>3.141592653589793</max_angle>
</horizontal>
<vertical>
<samples>32</samples>
<resolution>1</resolution>
<min_angle>-0.785</min_angle>
<max_angle>0.785</max_angle>
</vertical>
</scan>
<range>
<min>0.5</min>
<max>30.0</max>
<resolution>0.03</resolution>
</range>
</ray>
<plugin filename="libgazebo_ros_ouster_laser.so" name="gazebo_ros_laser_controller">
<topicName>/os1_cloud_node/points</topicName>
<frameName>os1_lidar</frameName>
<min_range>0.5</min_range>
<max_range>30.0</max_range>
<gaussianNoise>0.008</gaussianNoise>
</plugin>
</sensor>
</gazebo>
<!-- IMU -->
<gazebo>
<plugin filename="libhector_gazebo_ros_imu.so" name="imu_controller">
<robotNamespace>/</robotNamespace>
<updateRate>100.0</updateRate>
<bodyName>os1_imu</bodyName>
<topicName>/os1_cloud_node/imu</topicName>
<accelDrift>0.005 0.005 0.005</accelDrift>
<accelGaussianNoise>0.005 0.005 0.005</accelGaussianNoise>
<rateDrift>0.005 0.005 0.005 </rateDrift>
<rateGaussianNoise>0.005 0.005 0.005 </rateGaussianNoise>
<headingDrift>0.005</headingDrift>
<headingGaussianNoise>0.005</headingGaussianNoise>
</plugin>
</gazebo>
</robot>