Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014 import sys
00015
00016 if __name__=="__main__":
00017 if len(sys.argv) < 2:
00018 print "Usage:\n\tannotate_pr2dae.py [collada file]\n\nAnnoates the PR2 with the OpenRAVE profile tags.\nThis file will be in existence until URDF can support the extra information providedhere"
00019 sys.exit(0)
00020
00021 dae = open(sys.argv[1],'r').read()
00022 if dae.find('<extra type="collision">') < 0:
00023 index = dae.find('</kinematics_model>')
00024 dae = dae[:index] + """
00025 <extra type="collision">
00026 <technique profile="OpenRAVE">
00027 <ignore_link_pair link0="kmodel0/base_link" link1="kmodel0/br_caster_l_wheel_link"/>
00028 <ignore_link_pair link0="kmodel0/base_link" link1="kmodel0/br_caster_r_wheel_link"/>
00029 <ignore_link_pair link0="kmodel0/base_link" link1="kmodel0/fr_caster_l_wheel_link"/>
00030 <ignore_link_pair link0="kmodel0/base_link" link1="kmodel0/fr_caster_r_wheel_link"/>
00031 <ignore_link_pair link0="kmodel0/base_link" link1="kmodel0/fl_caster_l_wheel_link"/>
00032 <ignore_link_pair link0="kmodel0/base_link" link1="kmodel0/fl_caster_r_wheel_link"/>
00033 <ignore_link_pair link0="kmodel0/base_link" link1="kmodel0/bl_caster_l_wheel_link"/>
00034 <ignore_link_pair link0="kmodel0/base_link" link1="kmodel0/bl_caster_r_wheel_link"/>
00035 <ignore_link_pair link0="kmodel0/base_link" link1="kmodel0/l_shoulder_pan_link"/>
00036 <ignore_link_pair link0="kmodel0/base_link" link1="kmodel0/r_shoulder_pan_link"/>
00037 <ignore_link_pair link0="kmodel0/torso_lift_link" link1="kmodel0/l_shoulder_lift_link"/>
00038 <ignore_link_pair link0="kmodel0/torso_lift_link" link1="kmodel0/r_shoulder_lift_link"/>
00039 <ignore_link_pair link0="kmodel0/l_shoulder_pan_link" link1="kmodel0/l_upper_arm_roll_link"/>
00040 <ignore_link_pair link0="kmodel0/r_shoulder_pan_link" link1="kmodel0/r_upper_arm_roll_link"/>
00041 <ignore_link_pair link0="kmodel0/l_shoulder_pan_link" link1="kmodel0/l_upper_arm_link"/>
00042 <ignore_link_pair link0="kmodel0/r_shoulder_pan_link" link1="kmodel0/r_upper_arm_link"/>
00043 <ignore_link_pair link0="kmodel0/l_elbow_flex_link" link1="kmodel0/l_forearm_link"/>
00044 <ignore_link_pair link0="kmodel0/r_elbow_flex_link" link1="kmodel0/r_forearm_link"/>
00045 <ignore_link_pair link0="kmodel0/l_upper_arm_link" link1="kmodel0/l_forearm_roll_link"/>
00046 <ignore_link_pair link0="kmodel0/r_upper_arm_link" link1="kmodel0/r_forearm_roll_link"/>
00047 <ignore_link_pair link0="kmodel0/l_forearm_link" link1="kmodel0/l_gripper_palm_link"/>
00048 <ignore_link_pair link0="kmodel0/r_forearm_link" link1="kmodel0/r_gripper_palm_link"/>
00049 <ignore_link_pair link0="kmodel0/l_forearm_link" link1="kmodel0/l_wrist_roll_link"/>
00050 <ignore_link_pair link0="kmodel0/r_forearm_link" link1="kmodel0/r_wrist_roll_link"/>
00051 <ignore_link_pair link0="kmodel0/l_gripper_l_finger_link" link1="kmodel0/l_gripper_r_finger_link"/>
00052 <ignore_link_pair link0="kmodel0/r_gripper_l_finger_link" link1="kmodel0/r_gripper_r_finger_link"/>
00053 <ignore_link_pair link0="kmodel0/l_gripper_l_finger_tip_link" link1="kmodel0/l_gripper_r_finger_link"/>
00054 <ignore_link_pair link0="kmodel0/r_gripper_l_finger_tip_link" link1="kmodel0/r_gripper_r_finger_link"/>
00055 <ignore_link_pair link0="kmodel0/l_gripper_l_finger_link" link1="kmodel0/l_gripper_r_finger_tip_link"/>
00056 <ignore_link_pair link0="kmodel0/r_gripper_l_finger_link" link1="kmodel0/r_gripper_r_finger_tip_link"/>
00057 <ignore_link_pair link0="kmodel0/torso_lift_link" link1="kmodel0/head_tilt_link"/>
00058 </technique>
00059 </extra>
00060 """ + dae[index:]
00061
00062 if dae.find('<extra type="library_sensors"') < 0:
00063 index = dae.find('<scene>')
00064 dae = dae[:index] + """
00065 <extra type="library_sensors" id="libsensors">
00066 <technique profile="OpenRAVE">
00067 <sensor type="base_laser2d" id="base_laser">
00068 <angle_range>-130 129.75</angle_range>
00069 <distance_range>0.023 60.0</distance_range>
00070 <angle_increment>0.25</angle_increment>
00071 <time_increment>1.73611115315e-05</time_increment>
00072 <measurement_time>0.05</measurement_time>
00073 <interface_type>
00074 <technique profile="OpenRAVE">
00075 <interface>BaseLaser2D</interface>
00076 </technique>
00077 </interface_type>
00078 </sensor>
00079 <sensor type="base_laser2d" id="tilt_laser">
00080 <angle_range>-90 89.75</angle_range>
00081 <distance_range>0.023 10.0</distance_range>
00082 <angle_increment>0.25</angle_increment>
00083 <time_increment>1.73611115315e-05</time_increment>
00084 <measurement_time>0.025</measurement_time>
00085 <interface_type>
00086 <technique profile="OpenRAVE">
00087 <interface>BaseLaser2D</interface>
00088 </technique>
00089 </interface_type>
00090 </sensor>
00091 <sensor type="base_pinhole_camera" id="high_def_sensor">
00092 <image_dimensions>2448 2050 3</image_dimensions>
00093 <format>uint8</format>
00094 <measurement_time>0.05</measurement_time>
00095 <intrinsic>2955 0 1224.5 0 2955 1025.5</intrinsic>
00096 <distortion_model>0 0 0 0 0</distortion_model>
00097 <interface_type>
00098 <technique profile="OpenRAVE">
00099 <interface>BaseCamera</interface>
00100 </technique>
00101 </interface_type>
00102 </sensor>
00103 <sensor type="base_pinhole_camera" id="wide_l_stereo_camera_sensor">
00104 <image_dimensions>640 480 1</image_dimensions>
00105 <format>uint8</format>
00106 <measurement_time>0.04</measurement_time>
00107 <intrinsic>395.71449999999999 0.0 335.86279000000002 0.0 395.71449999999999 245.62557000000001</intrinsic>
00108 <distortion_model>0 0 0 0 0</distortion_model>
00109 <interface_type>
00110 <technique profile="OpenRAVE">
00111 <interface>BaseCamera</interface>
00112 </technique>
00113 </interface_type>
00114 </sensor>
00115 <sensor type="base_pinhole_camera" id="wide_r_stereo_camera_sensor">
00116 <image_dimensions>640 480 1</image_dimensions>
00117 <format>uint8</format>
00118 <measurement_time>0.04</measurement_time>
00119 <intrinsic>395.71449999999999 0.0 335.86279000000002 0.0 395.71449999999999 245.62557000000001</intrinsic>
00120 <distortion_model>0 0 0 0 0</distortion_model>
00121 <interface_type>
00122 <technique profile="OpenRAVE">
00123 <interface>BaseCamera</interface>
00124 </technique>
00125 </interface_type>
00126 </sensor>
00127 <sensor type="base_stereo_camera" id="wide_stereo_camera_sensor">
00128 <instance_sensor url="#wide_l_stereo_camera_sensor">
00129 <rectification>0.99956000000000012 0.0027200000000000002 -0.029390000000000003 -0.0027700000000000003 0.99999000000000005 -0.0016800000000000001 0.029390000000000003 0.0017600000000000001 0.99957000000000007</rectification>
00130 </instance_sensor>
00131 <instance_sensor url="#wide_r_stereo_camera_sensor">
00132 <rectification>0.99941000000000013 0.0035200000000000001 -0.034260000000000006 -0.0034600000000000004 0.99999000000000005 0.0017800000000000001 0.034270000000000002 -0.0016600000000000002 0.99941000000000013</rectification>
00133 </instance_sensor>
00134 </sensor>
00135 <sensor type="base_pinhole_camera" id="narrow_l_stereo_camera_sensor">
00136 <image_dimensions>640 480 1</image_dimensions>
00137 <format>uint8</format>
00138 <measurement_time>0.04</measurement_time>
00139 <intrinsic>772.55 0 320.05 0 772.55 240.5</intrinsic>
00140 <distortion_model type="plumb_bob">0 0 0 0 0</distortion_model>
00141 <interface_type>
00142 <technique profile="OpenRAVE">
00143 <interface>BaseCamera</interface>
00144 </technique>
00145 </interface_type>
00146 </sensor>
00147 <sensor type="base_pinhole_camera" id="narrow_r_stereo_camera_sensor">
00148 <image_dimensions>640 480 1</image_dimensions>
00149 <format>uint8</format>
00150 <measurement_time>0.04</measurement_time>
00151 <intrinsic>772.55 0 320.05 0 772.55 240.5</intrinsic>
00152 <distortion_model type="plumb_bob">0 0 0 0 0</distortion_model>
00153 <interface_type>
00154 <technique profile="OpenRAVE">
00155 <interface>BaseCamera</interface>
00156 </technique>
00157 </interface_type>
00158 </sensor>
00159 <sensor type="base_stereo_camera" id="narrow_stereo_camera_sensor">
00160 <instance_sensor url="#narrow_l_stereo_camera_sensor">
00161 <rectification>1 0 0 0 1 0 0 0 1</rectification>
00162 </instance_sensor>
00163 <instance_sensor url="#narrow_r_stereo_camera_sensor">
00164 <rectification>1 0 0 0 1 0 0 0 1</rectification>
00165 </instance_sensor>
00166 </sensor>
00167 <sensor type="base_pinhole_camera" id="l_forearm_cam_sensor">
00168 <image_dimensions>640 480 1</image_dimensions>
00169 <format>uint8</format>
00170 <measurement_time>0.04</measurement_time>
00171 <intrinsic>426.35142000000002 0.0 313.91464000000002 0.0 426.51092999999997 238.27394000000001</intrinsic>
00172 <distortion_model>0 0 0 0 0</distortion_model>
00173 <interface_type>
00174 <technique profile="OpenRAVE">
00175 <interface>BaseCamera</interface>
00176 </technique>
00177 </interface_type>
00178 </sensor>
00179 <sensor type="base_pinhole_camera" id="r_forearm_cam_sensor">
00180 <image_dimensions>640 480 1</image_dimensions>
00181 <format>uint8</format>
00182 <measurement_time>0.04</measurement_time>
00183 <intrinsic>430.5514 0.0 320.85068000000001 0.0 429.22170999999997 240.4314</intrinsic>
00184 <distortion_model>0 0 0 0 0</distortion_model>
00185 <interface_type>
00186 <technique profile="OpenRAVE">
00187 <interface>BaseCamera</interface>
00188 </technique>
00189 </interface_type>
00190 </sensor>
00191 </technique>
00192 </extra>
00193 """ + dae[index:]
00194
00195 manipulators = [('leftarm',"""
00196 <extra type="manipulator" name="leftarm">
00197 <technique profile="OpenRAVE">
00198 <frame_origin link="kmodel0/torso_lift_link"/>
00199 <frame_tip link="kmodel0/l_gripper_palm_link">
00200 <translate>0.18 0 0</translate>
00201 <rotate>0 1 0 90</rotate>
00202 </frame_tip>
00203 <gripper_joint joint="kmodel0/l_gripper_l_finger_joint">
00204 <closing_direction axis="./axis0">
00205 <float>-1</float>
00206 </closing_direction>
00207 </gripper_joint>
00208 <iksolver type="Transform6D">
00209 <free_joint joint="kmodel0/l_upper_arm_roll_joint"/>
00210 <interface_type>
00211 <technique profile="OpenRAVE">
00212 <interface>ikfast_pr2_leftarm</interface>
00213 </technique>
00214 </interface_type>
00215 </iksolver>
00216 </technique>
00217 </extra>
00218 """),
00219 ('leftarm_torso',"""
00220 <extra type="manipulator" name="leftarm_torso">
00221 <technique profile="OpenRAVE">
00222 <frame_origin link="kmodel0/base_link"/>
00223 <frame_tip link="kmodel0/l_gripper_palm_link">
00224 <translate>0.18 0 0</translate>
00225 <rotate>0 1 0 90</rotate>
00226 </frame_tip>
00227 <gripper_joint joint="kmodel0/l_gripper_l_finger_joint">
00228 <closing_direction axis="./axis0">
00229 <float>-1</float>
00230 </closing_direction>
00231 </gripper_joint>
00232 <iksolver type="Transform6D">
00233 <free_joint joint="kmodel0/torso_lift_joint"/>
00234 <free_joint joint="kmodel0/l_upper_arm_roll_joint"/>
00235 <interface_type>
00236 <technique profile="OpenRAVE">
00237 <interface>ikfast_pr2_leftarm_torso</interface>
00238 </technique>
00239 </interface_type>
00240 </iksolver>
00241 </technique>
00242 </extra>
00243 """),
00244 ('rightarm',"""
00245 <extra type="manipulator" name="rightarm">
00246 <technique profile="OpenRAVE">
00247 <frame_origin link="kmodel0/torso_lift_link"/>
00248 <frame_tip link="kmodel0/r_gripper_palm_link">
00249 <translate>0.18 0 0</translate>
00250 <rotate>0 1 0 90</rotate>
00251 </frame_tip>
00252 <gripper_joint joint="kmodel0/r_gripper_l_finger_joint">
00253 <closing_direction axis="./axis0">
00254 <float>-1</float>
00255 </closing_direction>
00256 </gripper_joint>
00257 <iksolver type="Transform6D">
00258 <free_joint joint="kmodel0/r_upper_arm_roll_joint"/>
00259 <interface_type>
00260 <technique profile="OpenRAVE">
00261 <interface>ikfast_pr2_rightarm</interface>
00262 </technique>
00263 </interface_type>
00264 </iksolver>
00265 </technique>
00266 </extra>
00267 """),
00268 ('rightarm_torso',"""
00269 <extra type="manipulator" name="rightarm_torso">
00270 <technique profile="OpenRAVE">
00271 <frame_origin link="kmodel0/base_link"/>
00272 <frame_tip link="kmodel0/r_gripper_palm_link">
00273 <translate>0.18 0 0</translate>
00274 <rotate>0 1 0 90</rotate>
00275 </frame_tip>
00276 <gripper_joint joint="kmodel0/r_gripper_l_finger_joint">
00277 <closing_direction axis="./axis0">
00278 <float>-1</float>
00279 </closing_direction>
00280 </gripper_joint>
00281 <iksolver type="Transform6D">
00282 <free_joint joint="kmodel0/torso_lift_joint"/>
00283 <free_joint joint="kmodel0/r_upper_arm_roll_joint"/>
00284 <interface_type>
00285 <technique profile="OpenRAVE">
00286 <interface>ikfast_pr2_rightarm_torso</interface>
00287 </technique>
00288 </interface_type>
00289 </iksolver>
00290 </technique>
00291 </extra>
00292 """),
00293 ('head',"""
00294 <extra type="manipulator" name="head">
00295 <technique profile="OpenRAVE">
00296 <frame_origin link="kmodel0/torso_lift_link"/>
00297 <frame_tip link="kmodel0/wide_stereo_optical_frame"/>
00298 <iksolver type="Lookat3D">
00299 <interface_type>
00300 <technique profile="OpenRAVE">
00301 <interface>ikfast_pr2_head</interface>
00302 </technique>
00303 </interface_type>
00304 </iksolver>
00305 </technique>
00306 </extra>
00307 """),
00308 ('head_torso',"""
00309 <extra type="manipulator" name="head_torso">
00310 <technique profile="OpenRAVE">
00311 <frame_origin link="kmodel0/base_link"/>
00312 <frame_tip link="kmodel0/wide_stereo_optical_frame"/>
00313 <iksolver type="Lookat3D">
00314 <free_joint joint="kmodel0/torso_lift_joint"/>
00315 <interface_type>
00316 <technique profile="OpenRAVE">
00317 <interface>ikfast_pr2_head_torso</interface>
00318 </technique>
00319 </interface_type>
00320 </iksolver>
00321 </technique>
00322 </extra>
00323 """),
00324 ('rightarm_camera',"""
00325 <extra type="manipulator" name="rightarm_camera">
00326 <technique profile="OpenRAVE">
00327 <frame_origin link="kmodel0/torso_lift_link"/>
00328 <frame_tip link="kmodel0/r_forearm_cam_optical_frame">
00329 </frame_tip>
00330 <iksolver type="Ray4D">
00331 </iksolver>
00332 </technique>
00333 </extra>
00334 """),
00335 ('leftarm_camera',"""
00336 <extra type="manipulator" name="leftarm_camera">
00337 <technique profile="OpenRAVE">
00338 <frame_origin link="kmodel0/torso_lift_link"/>
00339 <frame_tip link="kmodel0/l_forearm_cam_optical_frame">
00340 </frame_tip>
00341 <iksolver type="Ray4D">
00342 </iksolver>
00343 </technique>
00344 </extra>
00345 """)]
00346 sensors = [('base_laser',"""
00347 <extra type="attach_sensor" name="base_laser">
00348 <technique profile="OpenRAVE">
00349 <instance_sensor url="#base_laser"/>
00350 <frame_origin link="kmodel0/base_laser_link"/>
00351 </technique>
00352 </extra>
00353 """),
00354 ('tilt_laser',"""
00355 <extra type="attach_sensor" name="tilt_laser">
00356 <technique profile="OpenRAVE">
00357 <instance_sensor url="#tilt_laser"/>
00358 <frame_origin link="kmodel0/laser_tilt_link"/>
00359 </technique>
00360 </extra>
00361 """),
00362 ('l_forearm_cam_optical_sensor',"""
00363 <extra type="attach_sensor" name="l_forearm_cam_optical_sensor">
00364 <technique profile="OpenRAVE">
00365 <instance_sensor url="#l_forearm_cam_sensor"/>
00366 <frame_origin link="kmodel0/l_forearm_cam_optical_frame"/>
00367 </technique>
00368 </extra>
00369 """),
00370 ('r_forearm_cam_optical_sensor',"""
00371 <extra type="attach_sensor" name="r_forearm_cam_optical_sensor">
00372 <technique profile="OpenRAVE">
00373 <instance_sensor url="#l_forearm_cam_sensor"/>
00374 <frame_origin link="kmodel0/r_forearm_cam_optical_frame"/>
00375 </technique>
00376 </extra>
00377 """),
00378 ('narrow_stereo_optical_sensor',"""
00379 <extra type="attach_sensor" name="narrow_stereo_optical_sensor">
00380 <technique profile="OpenRAVE">
00381 <instance_sensor url="#narrow_stereo_camera_sensor"/>
00382 <frame_origin link="kmodel0/narrow_stereo_optical_frame"/>
00383 </technique>
00384 </extra>
00385 """),
00386 ('wide_stereo_optical_sensor',"""
00387 <extra type="attach_sensor" name="wide_stereo_optical_sensor">
00388 <technique profile="OpenRAVE">
00389 <instance_sensor url="#wide_stereo_camera_sensor"/>
00390 <frame_origin link="kmodel0/wide_stereo_optical_frame"/>
00391 </technique>
00392 </extra>
00393 """)]
00394 for name,xml in manipulators:
00395 if dae.find('<extra type="manipulator" name="%s">'%name) < 0:
00396 index = dae.find('</motion>')+9
00397 dae = dae[:index] + xml + dae[index:]
00398 for name,xml in sensors:
00399 if dae.find('<extra type="attach_sensor" name="%s">'%name) < 0:
00400 index = dae.find('</motion>')+9
00401 dae = dae[:index] + xml + dae[index:]
00402 open(sys.argv[1],'w').write(dae)