Skip to content

Commit dd9f9ca

Browse files
committed
Add sensor mount points from Rhys
1 parent 8783bb2 commit dd9f9ca

File tree

2 files changed

+50
-16
lines changed

2 files changed

+50
-16
lines changed

clearpath_platform_description/urdf/a300/attachments/observer_arch.urdf.xacro

+28-5
Original file line numberDiff line numberDiff line change
@@ -27,21 +27,44 @@
2727

2828
<!--
2929
Sensor mounting points
30-
TODO: get these measurements from Rhys
3130
-->
3231

3332
<link name="${name}_left_antenna_mount" />
34-
<joint name="${name}_left_antenna_joint" type="fixed">
33+
<joint name="${name}_left_antenna_mount_joint" type="fixed">
3534
<parent link="${name}_link" />
3635
<child link="${name}_left_antenna_mount" />
37-
<origin xyz="0 0.26 0.45" rpy="0 0 0" />
36+
<origin xyz="0 0.260 0.44536" rpy="0 0 0" />
3837
</joint>
3938

4039
<link name="${name}_right_antenna_mount" />
41-
<joint name="${name}_right_antenna_joint" type="fixed">
40+
<joint name="${name}_right_antenna_mount_joint" type="fixed">
4241
<parent link="${name}_link" />
4342
<child link="${name}_right_antenna_mount" />
44-
<origin xyz="0 -0.26 0.45" rpy="0 0 0" />
43+
<origin xyz="0 -0.260 0.44536" rpy="0 0 0" />
4544
</joint>
45+
46+
<link name="${name}_lidar_mount" />
47+
<joint name="${name}_lidar_mount_joint" type="fixed">
48+
<parent link="${name}_link" />
49+
<child link="${name}_lidar_mount" />
50+
<origin xyz="0.130 0 0.30256" rpy="3.14159 0 0" />
51+
</joint>
52+
53+
<!-- front-facing camera suspended under sensor arch -->
54+
<link name="${name}_front_camera_mount" />
55+
<joint name="${name}_front_camera_mount_joint" type="fixed">
56+
<parent link="${name}_link" />
57+
<child link="${name}_front_camera_mount" />
58+
<origin xyz="0.055 0 0.40896" rpy="3.14159 0 0" />
59+
</joint>
60+
61+
<!-- rear-facing camera suspended under sensor arch -->
62+
<link name="${name}_front_camera_mount" />
63+
<joint name="${name}_front_camera_mount_joint" type="fixed">
64+
<parent link="${name}_link" />
65+
<child link="${name}_front_camera_mount" />
66+
<origin xyz="-0.071992 0 0.4036838" rpy="0 -0.6021385919380436 3.14159" />
67+
</joint>
68+
4669
</xacro:macro>
4770
</robot>

clearpath_platform_description/urdf/a300/attachments/observer_backpack.urdf.xacro

+22-11
Original file line numberDiff line numberDiff line change
@@ -46,26 +46,37 @@
4646
<!--
4747
Mount points for sensors, other accessories
4848
-->
49+
50+
<!-- center of the adjustable track on top -->
4951
<link name="${name}_center_mount" />
5052
<joint name="${name}_center_joint" type="fixed">
5153
<parent link="${name}_enclosure_link" />
5254
<child link="${name}_center_mount" />
53-
<origin xyz="0 0 0.4" rpy="0 0 0" />
55+
<origin xyz="0 0 0.4074593" rpy="0 0 0" />
5456
</joint>
5557

56-
<link name="${name}_front_face_mount" />
57-
<joint name="${name}_front_face_link" type="fixed">
58-
<parent link="${name}_center_mount" />
59-
<child link="${name}_front_face_mount" />
60-
<origin xyz="0.33 0 -0.08" rpy="0 0 0" />
58+
<!-- standard rear-mounted antennas -->
59+
<link name="${name}_antenna_mount" />
60+
<joint name="${name}_antenna_mount_link" type="fixed">
61+
<parent link="${name}_enclosure_link" />
62+
<child link="${name}_antenna_mount" />
63+
<origin xyz="-0.4028 0 0.4074593" rpy="0 0 0" />
6164
</joint>
6265

63-
<link name="${name}_rear_face_mount" />
64-
<joint name="${name}_rear_face_link" type="fixed">
65-
<parent link="${name}_center_mount" />
66-
<child link="${name}_rear_face_mount" />
67-
<origin xyz="-0.33 0 -0.08" rpy="0 0 3.1459" />
66+
<!-- rear-mounted fixposition -->
67+
<link name="${name}_ins_mount" />
68+
<joint name="${name}_ins_mouint_link" type="fixed">
69+
<parent link="${name}_enclosure_link" />
70+
<child link="${name}_ins_mount" />
71+
<origin xyz="-0.4 0.0 0.3192593" rpy="3.14159 0 0" />
6872
</joint>
6973

74+
<!-- front-mounted robin -->
75+
<link name="${name}_front_lidar_mount" />
76+
<joint name="${name}_front_lidar_mount_link" type="fixed">
77+
<parent link="${name}_enclosure_link" />
78+
<child link="${name}_front_lidar_mount" />
79+
<origin xyz="0.40 0 0.2708593" rpy="0 0 0" />
80+
</joint>
7081
</xacro:macro>
7182
</robot>

0 commit comments

Comments
 (0)