baxter.world
Go to the documentation of this file.
1 
3 [LINKS]
4 
5  base
6  torso : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_torso_0.off" color (0.5,0.5,0.5) decoration
7  body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_torso_1.off" hidden
8 
9  left_torso_itb
10  right_torso_itb
11  pedestal : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_pedestal_0.off" color (0.2,0.2,0.2) decoration
12  body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_pedestal_1.off" hidden
13 
14  head : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_head_0.off" color (0.2,0.2,0.2) decoration
15  sphere 0.001 (0,0,0) hidden
16 
17  sonar_ring : cylinder 0.085 (-0.0347000000000000,0,0.0045300000000000) (-0.0347000000000000,0,0.0145300000000000) color (0.2,0.2,0.2) decoration
18  sphere 0.001 (0,0,0) hidden
19 
20  screen : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_screen_0.off" color (0.5,0.1,0.1) decoration
21  sphere 0.001 (0,0,0) hidden
22 
23  head_camera
24  dummyhead1
25  collision_head_link_1 : sphere 0.001 (0,0,0) color (0.8,0.3,0.3) decoration
26  sphere 0.22 (-0.0700000000000000,-0.0400000000000000,0) hidden
27 
28  collision_head_link_2 : sphere 0.001 (0,0,0) color (0.8,0.3,0.3) decoration
29  sphere 0.22 (-0.0700000000000000,0.0400000000000000,0) hidden
30 
31  right_arm_mount
32  right_upper_shoulder : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_right_upper_shoulder_0.off" color (0.5,0.1,0.1) decoration
33  cylinder 0.06 (0,0,0) (0,0,0.2722000000000000) hidden
34 
35  right_lower_shoulder : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_right_lower_shoulder_0.off" color (0.5,0.1,0.1) decoration
36  cylinder 0.06 (0,0,-0.0600000000000000) (0,0,0.0600000000000000) hidden
37 
38  right_upper_elbow : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_right_upper_elbow_0.off" color (0.5,0.1,0.1) decoration
39  cylinder 0.06 (0,0,-0.1070000000000000) (0,0,0) hidden
40 
41  right_upper_elbow_visual : cylinder 0.06 (0,0,0) (0,0,0.2730000000000000) hidden
42 
43  right_lower_elbow : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_right_lower_elbow_0.off" color (0.5,0.1,0.1) decoration
44  cylinder 0.06 (0,0,-0.0500000000000000) (0,0,0.0500000000000000) hidden
45 
46  right_upper_forearm : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_right_upper_forearm_0.off" color (0.5,0.1,0.1) decoration
47  cylinder 0.06 (0,0,-0.0880000000000000) (0,0,0) hidden
48 
49  right_upper_forearm_visual : cylinder 0.06 (0,0,0) (0,0,0.2720000000000000) hidden
50 
51  right_arm_itb
52  right_lower_forearm : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_right_lower_forearm_0.off" color (0.5,0.1,0.1) decoration
53  cylinder 0.06 (0,0,-0.0500000000000000) (0,0,0.0500000000000000) hidden
54 
55  right_wrist : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_right_wrist_0.off" color (0.1,0.1,0.1) decoration
56  cylinder 0.06 (0,0,-0.0825000000000000) (0,0,0.0825000000000000) hidden
57 
58  right_hand : cylinder 0.04 (0,0,-0.0464000000000000) (0,0,0) hidden
59 
60  right_hand_camera : cylinder 0.02 (0,0,-0.0050000000000000) (0,0,0.0050000000000000) color (0,0,1) decoration
61 
62  right_hand_camera_axis
63  right_hand_range : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_right_hand_range_0.off" color (0,0,1) decoration
64 
65  right_gripper_base : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_right_gripper_base_0.off" color (0.5,0.1,0.1) decoration
66 
67  right_gripper : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_right_gripper_0.off" color (0,0,0) decoration
68 
69  left_arm_mount
70  left_upper_shoulder : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_left_upper_shoulder_0.off" color (0.5,0.1,0.1) decoration
71  cylinder 0.06 (0,0,0) (0,0,0.2722000000000000) hidden
72 
73  left_lower_shoulder : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_left_lower_shoulder_0.off" color (0.5,0.1,0.1) decoration
74  cylinder 0.06 (0,0,-0.0600000000000000) (0,0,0.0600000000000000) hidden
75 
76  left_upper_elbow : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_left_upper_elbow_0.off" color (0.5,0.1,0.1) decoration
77  cylinder 0.06 (0,0,-0.1070000000000000) (0,0,0) hidden
78 
79  left_upper_elbow_visual : cylinder 0.06 (0,0,0) (0,0,0.2730000000000000) hidden
80 
81  left_lower_elbow : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_left_lower_elbow_0.off" color (0.5,0.1,0.1) decoration
82  cylinder 0.06 (0,0,-0.0500000000000000) (0,0,0.0500000000000000) hidden
83 
84  left_upper_forearm : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_left_upper_forearm_0.off" color (0.5,0.1,0.1) decoration
85  cylinder 0.06 (0,0,-0.0880000000000000) (0,0,0) hidden
86 
87  left_upper_forearm_visual : cylinder 0.06 (0,0,0) (0,0,0.2720000000000000) hidden
88 
89  left_arm_itb
90  left_lower_forearm : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_left_lower_forearm_0.off" color (0.5,0.1,0.1) decoration
91  cylinder 0.06 (0,0,-0.0500000000000000) (0,0,0.0500000000000000) hidden
92 
93  left_wrist : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_left_wrist_0.off" color (0.1,0.1,0.1) decoration
94  cylinder 0.06 (0,0,-0.0825000000000000) (0,0,0.0825000000000000) hidden
95 
96  left_hand : cylinder 0.04 (0,0,-0.0464000000000000) (0,0,0) hidden
97 
98  left_hand_camera : cylinder 0.02 (0,0,-0.0050000000000000) (0,0,0.0050000000000000) color (0,0,1) decoration
99 
100  left_hand_camera_axis
101  left_hand_range : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_left_hand_range_0.off" color (0,0,1) decoration
102 
103  left_gripper_base : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_left_gripper_base_0.off" color (0.5,0.1,0.1) decoration
104 
105  left_gripper : body "/Users/porta/cuik/CuikSuite/examples/Baxter/bodies/baxter_left_gripper_0.off" color (0,0,0) decoration
106 
107 [JOINTS]
108 
109  fix: base collision_head_link_1 Txyz(0.11,0,0.75)
110 
111  fix: base collision_head_link_2 Txyz(0.11,0,0.75)
112 
113  fix: head dummyhead1 ID
114 
115  fix: base torso ID
116 
117  fix: torso left_torso_itb Txyz(-0.08897,0.15593,0.389125)*Rz(3.1415926535897931)*Ry(0.0000000000000001)*Rx(1.5707963267948966)
118 
119  fix: torso right_torso_itb Txyz(-0.08897,-0.15593,0.389125)*Rx(1.5707963267948966)
120 
121  fix: torso pedestal ID
122 
123  revolute: torso (0.0600000000000000,0.0000000000000000,0.6860000000000001) (0.0600000000000000,0.0000000000000000,1.6859999999999999)
124  head (0.0000000000000000,0.0000000000000000,0.0000000000000000) (0.0000000000000000,0.0000000000000000,1.0000000000000000)
125  range [-1.57079632679,1.57079632679] +(1.0000000000000000,0.0000000000000000,0.0000000000000000) +(1.0000000000000000,0.0000000000000000,0.0000000000000000)
126 
127  fix: head screen Txyz(0.1227,0,0)*Rz(1.5707963267948966)*Rx(1.7505700000000000)
128 
129  fix: head head_camera Txyz(0.12839,0,0.06368)*Rz(1.5707963267948966)*Rx(1.7505700000000000)
130 
131  fix: torso sonar_ring Txyz(0.0947,0,0.817)
132 
133  fix: torso right_arm_mount Txyz(0.024645,-0.219645,0.118588)*Rz(-0.7853999999999999)
134 
135  revolute: right_arm_mount (0.0556950000000000,0.0000000000000000,0.0110380000000000) (0.0556950000000000,0.0000000000000000,1.0110380000000001)
136  right_upper_shoulder (0.0000000000000000,0.0000000000000000,0.0000000000000000) (0.0000000000000000,0.0000000000000000,1.0000000000000000)
137  range [-1.70167993878,1.70167993878] +(1.0000000000000000,0.0000000000000000,0.0000000000000000) +(1.0000000000000000,0.0000000000000000,0.0000000000000000)
138 
139  revolute: right_upper_shoulder (0.0690000000000000,0.0000000000000000,0.2703500000000000) (0.0690000000000000,1.0000000000000000,0.2703500000000000)
140  right_lower_shoulder (0.0000000000000000,0.0000000000000000,0.0000000000000000) (0.0000000000000000,0.0000000000000000,1.0000000000000000)
141  range [-2.147,1.047] +(1.0000000000000000,0.0000000000000000,0.0000000000000000) +(1.0000000000000000,0.0000000000000000,0.0000000000000000)
142 
143  revolute: right_lower_shoulder (0.1020000000000000,0.0000000000000000,0.0000000000000000) (1.1020000000000001,0.0000000000000000,0.0000000000000000)
144  right_upper_elbow (0.0000000000000000,0.0000000000000000,0.0000000000000000) (0.0000000000000000,0.0000000000000000,1.0000000000000000)
145  range [-3.05417993878,3.05417993878] +(0.0000000000000001,1.0000000000000000,0.0000000000000000) +(1.0000000000000000,0.0000000000000000,0.0000000000000000)
146 
147  fix: right_lower_shoulder right_upper_elbow_visual Txyz(0.107,0,0)*Rz(1.5707963267948966)*Rx(1.5707963267948966)
148 
149  revolute: right_upper_elbow (0.0690000000000000,0.0000000000000000,0.2624200000000000) (0.0690000000000000,1.0000000000000000,0.2624200000000000)
150  right_lower_elbow (0.0000000000000000,0.0000000000000000,0.0000000000000000) (0.0000000000000000,0.0000000000000000,1.0000000000000000)
151  range [-0.05,2.618] +(0.0000000000000001,0.0000000000000000,1.0000000000000000) +(1.0000000000000000,0.0000000000000000,0.0000000000000000)
152 
153  revolute: right_lower_elbow (0.1035900000000000,0.0000000000000000,0.0000000000000000) (1.1035900000000001,0.0000000000000000,0.0000000000000000)
154  right_upper_forearm (0.0000000000000000,0.0000000000000000,0.0000000000000000) (0.0000000000000000,0.0000000000000000,1.0000000000000000)
155  range [-3.059,3.059] +(0.0000000000000001,1.0000000000000000,0.0000000000000000) +(1.0000000000000000,0.0000000000000000,0.0000000000000000)
156 
157  fix: right_lower_elbow right_upper_forearm_visual Txyz(0.088,0,0)*Rz(1.5707963267948966)*Rx(1.5707963267948966)
158 
159  fix: right_upper_forearm right_arm_itb Txyz(-0.0565,0,0.12)*Rz(1.5707963267948966)*Rx(-1.5707963267948966)
160 
161  revolute: right_upper_forearm (0.0100000000000000,0.0000000000000000,0.2707000000000000) (0.0099999999999999,1.0000000000000000,0.2707000000000000)
162  right_lower_forearm (0.0000000000000000,0.0000000000000000,0.0000000000000000) (0.0000000000000000,0.0000000000000000,1.0000000000000000)
163  range [-1.57079632679,2.094] +(0.0000000000000001,0.0000000000000000,1.0000000000000000) +(1.0000000000000000,0.0000000000000000,0.0000000000000000)
164 
165  revolute: right_lower_forearm (0.1159750000000000,0.0000000000000000,0.0000000000000000) (1.1159749999999999,0.0000000000000000,0.0000000000000000)
166  right_wrist (0.0000000000000000,0.0000000000000000,0.0000000000000000) (0.0000000000000000,0.0000000000000000,1.0000000000000000)
167  range [-3.059,3.059] +(0.0000000000000001,1.0000000000000000,0.0000000000000000) +(1.0000000000000000,0.0000000000000000,0.0000000000000000)
168 
169  fix: right_wrist right_hand Txyz(0,0,0.11355)
170 
171  fix: right_hand right_hand_camera Txyz(0.03825,0.012,0.015355)*Rz(-1.5707963267948966)
172 
173  fix: right_hand right_hand_camera_axis Txyz(0.03825,0.012,0.015355)
174 
175  fix: right_hand right_hand_range Txyz(0.032,-0.020245,0.0288)*Rz(-1.5707963267948966)*Ry(-1.5707963267948966)
176 
177  fix: right_hand right_gripper_base ID
178 
179  fix: right_gripper_base right_gripper Txyz(0,0,0.025)
180 
181  fix: torso left_arm_mount Txyz(0.024645,0.219645,0.118588)*Rz(0.7853999999999999)
182 
183  revolute: left_arm_mount (0.0556950000000000,0.0000000000000000,0.0110380000000000) (0.0556950000000000,0.0000000000000000,1.0110380000000001)
184  left_upper_shoulder (0.0000000000000000,0.0000000000000000,0.0000000000000000) (0.0000000000000000,0.0000000000000000,1.0000000000000000)
185  range [-1.70167993878,1.70167993878] +(1.0000000000000000,0.0000000000000000,0.0000000000000000) +(1.0000000000000000,0.0000000000000000,0.0000000000000000)
186 
187  revolute: left_upper_shoulder (0.0690000000000000,0.0000000000000000,0.2703500000000000) (0.0690000000000000,1.0000000000000000,0.2703500000000000)
188  left_lower_shoulder (0.0000000000000000,0.0000000000000000,0.0000000000000000) (0.0000000000000000,0.0000000000000000,1.0000000000000000)
189  range [-2.147,1.047] +(1.0000000000000000,0.0000000000000000,0.0000000000000000) +(1.0000000000000000,0.0000000000000000,0.0000000000000000)
190 
191  revolute: left_lower_shoulder (0.1020000000000000,0.0000000000000000,0.0000000000000000) (1.1020000000000001,0.0000000000000000,0.0000000000000000)
192  left_upper_elbow (0.0000000000000000,0.0000000000000000,0.0000000000000000) (0.0000000000000000,0.0000000000000000,1.0000000000000000)
193  range [-3.05417993878,3.05417993878] +(0.0000000000000001,1.0000000000000000,0.0000000000000000) +(1.0000000000000000,0.0000000000000000,0.0000000000000000)
194 
195  fix: left_lower_shoulder left_upper_elbow_visual Txyz(0.107,0,0)*Rz(1.5707963267948966)*Rx(1.5707963267948966)
196 
197  revolute: left_upper_elbow (0.0690000000000000,0.0000000000000000,0.2624200000000000) (0.0690000000000000,1.0000000000000000,0.2624200000000000)
198  left_lower_elbow (0.0000000000000000,0.0000000000000000,0.0000000000000000) (0.0000000000000000,0.0000000000000000,1.0000000000000000)
199  range [-0.05,2.618] +(0.0000000000000001,0.0000000000000000,1.0000000000000000) +(1.0000000000000000,0.0000000000000000,0.0000000000000000)
200 
201  revolute: left_lower_elbow (0.1035900000000000,0.0000000000000000,0.0000000000000000) (1.1035900000000001,0.0000000000000000,0.0000000000000000)
202  left_upper_forearm (0.0000000000000000,0.0000000000000000,0.0000000000000000) (0.0000000000000000,0.0000000000000000,1.0000000000000000)
203  range [-3.059,3.059] +(0.0000000000000001,1.0000000000000000,0.0000000000000000) +(1.0000000000000000,0.0000000000000000,0.0000000000000000)
204 
205  fix: left_lower_elbow left_upper_forearm_visual Txyz(0.088,0,0)*Rz(1.5707963267948966)*Rx(1.5707963267948966)
206 
207  fix: left_upper_forearm left_arm_itb Txyz(-0.0565,0,0.12)*Rz(1.5707963267948966)*Rx(-1.5707963267948966)
208 
209  revolute: left_upper_forearm (0.0100000000000000,0.0000000000000000,0.2707000000000000) (0.0099999999999999,1.0000000000000000,0.2707000000000000)
210  left_lower_forearm (0.0000000000000000,0.0000000000000000,0.0000000000000000) (0.0000000000000000,0.0000000000000000,1.0000000000000000)
211  range [-1.57079632679,2.094] +(0.0000000000000001,0.0000000000000000,1.0000000000000000) +(1.0000000000000000,0.0000000000000000,0.0000000000000000)
212 
213  revolute: left_lower_forearm (0.1159750000000000,0.0000000000000000,0.0000000000000000) (1.1159749999999999,0.0000000000000000,0.0000000000000000)
214  left_wrist (0.0000000000000000,0.0000000000000000,0.0000000000000000) (0.0000000000000000,0.0000000000000000,1.0000000000000000)
215  range [-3.059,3.059] +(0.0000000000000001,1.0000000000000000,0.0000000000000000) +(1.0000000000000000,0.0000000000000000,0.0000000000000000)
216 
217  fix: left_wrist left_hand Txyz(0,0,0.11355)
218 
219  fix: left_hand left_hand_camera Txyz(0.03825,0.012,0.015355)*Rz(-1.5707963267948966)
220 
221  fix: left_hand left_hand_camera_axis Txyz(0.03825,0.012,0.015355)
222 
223  fix: left_hand left_hand_range Txyz(0.032,-0.020245,0.0288)*Rz(-1.5707963267948966)*Ry(-1.5707963267948966)
224 
225  fix: left_hand left_gripper_base ID
226 
227  fix: left_gripper_base left_gripper Txyz(0,0,0.025)
228 
229