Skip to content

Commit 98ccc7c

Browse files
author
Florian Weißhardt
committed
Merge pull request #42 from ipa-nhg/groovy_dev_cob4
cob4 integration
2 parents 6bbdb22 + aaabe6b commit 98ccc7c

File tree

1 file changed

+109
-0
lines changed

1 file changed

+109
-0
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,109 @@
1+
<?xml version="1.0" ?><robot>
2+
<!-- ***************** -->
3+
<!-- base calibration -->
4+
<!-- ***************** -->
5+
<!-- laser front mount positions | relative to base_link -->
6+
<property name="offset_laser_front_x" value="0.0"/>
7+
<property name="offset_laser_front_y" value="0.0"/>
8+
<property name="offset_laser_front_z" value="0.0"/>
9+
<property name="offset_laser_front_roll" value="0.0"/>
10+
<property name="offset_laser_front_pitch" value="0.0"/>
11+
<property name="offset_laser_front_yaw" value="0.0"/>
12+
13+
<!-- laser rear mount positions | relative to base_link -->
14+
<property name="offset_laser_left_x" value="0.0"/>
15+
<property name="offset_laser_left_y" value="0.0"/>
16+
<property name="offset_laser_left_z" value="0.0"/>
17+
<property name="offset_laser_left_roll" value="0.0"/>
18+
<property name="offset_laser_left_pitch" value="0.0"/>
19+
<property name="offset_laser_left_yaw" value="0.0"/>
20+
21+
<!-- laser top mount positions | relative to base_link -->
22+
<property name="offset_laser_right_x" value="0.0"/>
23+
<property name="offset_laser_right_y" value="0.0"/>
24+
<property name="offset_laser_right_z" value="0.0"/>
25+
<property name="offset_laser_right_roll" value="0.0"/>
26+
<property name="offset_laser_right_pitch" value="0.0"/>
27+
<property name="offset_laser_right_yaw" value="0.0"/>
28+
29+
<!-- *********************** -->
30+
<!-- upper robot calibration -->
31+
<!-- *********************** -->
32+
33+
<!-- torso mount positions | relative to base_link -->
34+
<property name="offset_torso_x" value="0.0"/>
35+
<property name="offset_torso_y" value="0.0"/>
36+
<property name="offset_torso_z" value="0.0"/>
37+
<property name="offset_torso_roll" value="0.0"/>
38+
<property name="offset_torso_pitch" value="0.0"/>
39+
<property name="offset_torso_yaw" value="0.0"/>
40+
41+
<!-- head mount positions | relative to torso_3_link -->
42+
<property name="offset_head_x" value="0.0"/>
43+
<property name="offset_head_y" value="0.0"/>
44+
<property name="offset_head_z" value="0.0"/>
45+
<property name="offset_head_roll" value="0.0"/>
46+
<property name="offset_head_pitch" value="0.0"/>
47+
<property name="offset_head_yaw" value="0.0"/>
48+
49+
<!-- sersorring mount positions | relative to head_3_link -->
50+
<property name="offset_sensorring_x" value="0.0"/>
51+
<property name="offset_sensorring_y" value="0.0"/>
52+
<property name="offset_sensorring_z" value="0.0"/>
53+
<property name="offset_sensorring_roll" value="0.0"/>
54+
<property name="offset_sensorring_pitch" value="0.0"/>
55+
<property name="offset_sensorring_yaw" value="0.0"/>
56+
57+
<!-- arm right mount positions | relative to torso_3_link -->
58+
<property name="offset_arm_right_x" value="0.0"/>
59+
<property name="offset_arm_right_y" value="0.0"/>
60+
<property name="offset_arm_right_z" value="0.0"/>
61+
<property name="offset_arm_right_roll" value="0.0"/>
62+
<property name="offset_arm_right_pitch" value="0.0"/>
63+
<property name="offset_arm_right_yaw" value="0.0"/>
64+
65+
<!-- arm left mount positions | relative to torso_3_link -->
66+
<property name="offset_arm_left_x" value="0.0"/>
67+
<property name="offset_arm_left_y" value="0.0"/>
68+
<property name="offset_arm_left_z" value="0.0"/>
69+
<property name="offset_arm_left_roll" value="0.0"/>
70+
<property name="offset_arm_left_pitch" value="0.0"/>
71+
<property name="offset_arm_left_yaw" value="0.0"/>
72+
73+
<!-- *********************************** -->
74+
<!-- kinematic chain reference positions -->
75+
<!-- *********************************** -->
76+
77+
<!-- torso offset positions | used as calibration_rising for torso chain -->
78+
<!-- ! set these values to make torso straight with (0, 0, 0) joint angles ! -->
79+
<property name="offset_torso_1_ref" value="0.0"/>
80+
<property name="offset_torso_2_ref" value="0.0"/>
81+
<property name="offset_torso_3_ref" value="0.0"/>
82+
83+
<!-- head offset positions | used as calibration_rising for head axis chain -->
84+
<property name="offset_head_1_ref" value="0.0"/>
85+
<property name="offset_head_2_ref" value="0.0"/>
86+
<property name="offset_head_3_ref" value="0.0"/>
87+
88+
<property name="offset_sensorring_ref" value="0.0"/>
89+
90+
<!-- arm right offset positions | used as calibration_rising for arm chain-->
91+
<property name="offset_arm_right_1_ref" value="0.0"/>
92+
<property name="offset_arm_right_2_ref" value="0.0"/>
93+
<property name="offset_arm_right_3_ref" value="0.0"/>
94+
<property name="offset_arm_right_4_ref" value="0.0"/>
95+
<property name="offset_arm_right_5_ref" value="0.0"/>
96+
<property name="offset_arm_right_6_ref" value="0.0"/>
97+
<property name="offset_arm_right_7_ref" value="0.0"/>
98+
99+
<!-- arm left offset positions | used as calibration_rising for arm chain-->
100+
<property name="offset_arm_left_1_ref" value="0.0"/>
101+
<property name="offset_arm_left_2_ref" value="0.0"/>
102+
<property name="offset_arm_left_3_ref" value="0.0"/>
103+
<property name="offset_arm_left_4_ref" value="0.0"/>
104+
<property name="offset_arm_left_5_ref" value="0.0"/>
105+
<property name="offset_arm_left_6_ref" value="0.0"/>
106+
<property name="offset_arm_left_7_ref" value="0.0"/>
107+
108+
109+
</robot>

0 commit comments

Comments
 (0)