Variables
annotate_pr2dae Namespace Reference

Variables

tuple dae = open(sys.argv[1],'r')
tuple index = dae.find('</kinematics_model>')
list manipulators
list sensors

Variable Documentation

list annotate_pr2dae::dae = open(sys.argv[1],'r')

Definition at line 21 of file annotate_pr2dae.py.

tuple annotate_pr2dae::index = dae.find('</kinematics_model>')

Definition at line 23 of file annotate_pr2dae.py.

Initial value:
00001 [('leftarm',"""            <extra type="manipulator" name="leftarm">              <technique profile="OpenRAVE">                <frame_origin link="kmodel0/torso_lift_link"/>                <frame_tip link="kmodel0/l_gripper_palm_link">                  <translate>0.18 0 0</translate>                  <rotate>0 1 0 90</rotate>                </frame_tip>                <gripper_joint joint="kmodel0/l_gripper_l_finger_joint">                  <closing_direction axis="./axis0">                    <float>-1</float>                  </closing_direction>                </gripper_joint>                <iksolver type="Transform6D">                  <free_joint joint="kmodel0/l_upper_arm_roll_joint"/>                  <interface_type>                    <technique profile="OpenRAVE">                      <interface>ikfast_pr2_leftarm</interface>                    </technique>                  </interface_type>                </iksolver>              </technique>            </extra>"""),
00002                     ('leftarm_torso',"""            <extra type="manipulator" name="leftarm_torso">              <technique profile="OpenRAVE">                <frame_origin link="kmodel0/base_link"/>                <frame_tip link="kmodel0/l_gripper_palm_link">                  <translate>0.18 0 0</translate>                  <rotate>0 1 0 90</rotate>                </frame_tip>                <gripper_joint joint="kmodel0/l_gripper_l_finger_joint">                  <closing_direction axis="./axis0">                    <float>-1</float>                  </closing_direction>                </gripper_joint>                <iksolver type="Transform6D">                  <free_joint joint="kmodel0/torso_lift_joint"/>                  <free_joint joint="kmodel0/l_upper_arm_roll_joint"/>                  <interface_type>                    <technique profile="OpenRAVE">                      <interface>ikfast_pr2_leftarm_torso</interface>                    </technique>                  </interface_type>                </iksolver>              </technique>            </extra>"""),
00003                     ('rightarm',"""            <extra type="manipulator" name="rightarm">              <technique profile="OpenRAVE">                <frame_origin link="kmodel0/torso_lift_link"/>                <frame_tip link="kmodel0/r_gripper_palm_link">                  <translate>0.18 0 0</translate>                  <rotate>0 1 0 90</rotate>                </frame_tip>                <gripper_joint joint="kmodel0/r_gripper_l_finger_joint">                  <closing_direction axis="./axis0">                    <float>-1</float>                  </closing_direction>                </gripper_joint>                <iksolver type="Transform6D">                  <free_joint joint="kmodel0/r_upper_arm_roll_joint"/>                  <interface_type>                    <technique profile="OpenRAVE">                      <interface>ikfast_pr2_rightarm</interface>                    </technique>                  </interface_type>                </iksolver>              </technique>            </extra>"""),
00004                     ('rightarm_torso',"""            <extra type="manipulator" name="rightarm_torso">              <technique profile="OpenRAVE">                <frame_origin link="kmodel0/base_link"/>                <frame_tip link="kmodel0/r_gripper_palm_link">                  <translate>0.18 0 0</translate>                  <rotate>0 1 0 90</rotate>                </frame_tip>                <gripper_joint joint="kmodel0/r_gripper_l_finger_joint">                  <closing_direction axis="./axis0">                    <float>-1</float>                  </closing_direction>                </gripper_joint>                <iksolver type="Transform6D">                  <free_joint joint="kmodel0/torso_lift_joint"/>                  <free_joint joint="kmodel0/r_upper_arm_roll_joint"/>                  <interface_type>                    <technique profile="OpenRAVE">                      <interface>ikfast_pr2_rightarm_torso</interface>                    </technique>                  </interface_type>                </iksolver>              </technique>            </extra>"""),
00005                     ('head',"""            <extra type="manipulator" name="head">              <technique profile="OpenRAVE">                <frame_origin link="kmodel0/torso_lift_link"/>                <frame_tip link="kmodel0/wide_stereo_optical_frame"/>                <iksolver type="Lookat3D">                  <interface_type>                    <technique profile="OpenRAVE">                      <interface>ikfast_pr2_head</interface>                    </technique>                  </interface_type>                </iksolver>              </technique>            </extra>"""),
00006                     ('head_torso',"""            <extra type="manipulator" name="head_torso">              <technique profile="OpenRAVE">                <frame_origin link="kmodel0/base_link"/>                <frame_tip link="kmodel0/wide_stereo_optical_frame"/>                <iksolver type="Lookat3D">                  <free_joint joint="kmodel0/torso_lift_joint"/>                  <interface_type>                    <technique profile="OpenRAVE">                      <interface>ikfast_pr2_head_torso</interface>                    </technique>                  </interface_type>                </iksolver>              </technique>            </extra>"""),
00007                     ('rightarm_camera',"""            <extra type="manipulator" name="rightarm_camera">              <technique profile="OpenRAVE">                <frame_origin link="kmodel0/torso_lift_link"/>                <frame_tip link="kmodel0/r_forearm_cam_optical_frame">                </frame_tip>                <iksolver type="Ray4D">                </iksolver>              </technique>            </extra>"""),
00008                     ('leftarm_camera',"""            <extra type="manipulator" name="leftarm_camera">              <technique profile="OpenRAVE">                <frame_origin link="kmodel0/torso_lift_link"/>                <frame_tip link="kmodel0/l_forearm_cam_optical_frame">                </frame_tip>                <iksolver type="Ray4D">                </iksolver>              </technique>            </extra>""")]

Definition at line 195 of file annotate_pr2dae.py.

Initial value:
00001 [('base_laser',"""            <extra type="attach_sensor" name="base_laser">              <technique profile="OpenRAVE">                <instance_sensor url="#base_laser"/>                <frame_origin link="kmodel0/base_laser_link"/>              </technique>            </extra>"""),
00002                ('tilt_laser',"""            <extra type="attach_sensor" name="tilt_laser">              <technique profile="OpenRAVE">                <instance_sensor url="#tilt_laser"/>                <frame_origin link="kmodel0/laser_tilt_link"/>              </technique>            </extra>"""),
00003                ('l_forearm_cam_optical_sensor',"""            <extra type="attach_sensor" name="l_forearm_cam_optical_sensor">              <technique profile="OpenRAVE">                <instance_sensor url="#l_forearm_cam_sensor"/>                <frame_origin link="kmodel0/l_forearm_cam_optical_frame"/>              </technique>            </extra>"""),
00004                ('r_forearm_cam_optical_sensor',"""            <extra type="attach_sensor" name="r_forearm_cam_optical_sensor">              <technique profile="OpenRAVE">                <instance_sensor url="#l_forearm_cam_sensor"/>                <frame_origin link="kmodel0/r_forearm_cam_optical_frame"/>              </technique>            </extra>"""),
00005                ('narrow_stereo_optical_sensor',"""            <extra type="attach_sensor" name="narrow_stereo_optical_sensor">              <technique profile="OpenRAVE">                <instance_sensor url="#narrow_stereo_camera_sensor"/>                <frame_origin link="kmodel0/narrow_stereo_optical_frame"/>              </technique>            </extra>"""),
00006                ('wide_stereo_optical_sensor',"""            <extra type="attach_sensor" name="wide_stereo_optical_sensor">              <technique profile="OpenRAVE">                <instance_sensor url="#wide_stereo_camera_sensor"/>                <frame_origin link="kmodel0/wide_stereo_optical_frame"/>              </technique>            </extra>""")]

Definition at line 346 of file annotate_pr2dae.py.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


orrosplanning
Author(s): Rosen Diankov (rosen.diankov@gmail.com)
autogenerated on Sat Mar 23 2013 22:33:10