nao_dictionaries.py
Go to the documentation of this file.
00001 import math
00002 import naoqi_tools.urdf as ur
00003 pi_2 = math.pi/2.0
00004 
00005 Nao_offsets = {
00006     #### sensors offsets  ####
00007     # cameras
00008     'CameraTopV4OffsetX':5.871e-2,
00009     'CameraTopV4OffsetY':0.0,
00010     'CameraTopV4OffsetZ':6.364e-2,
00011     'CameraTopV4RotX':0.0,
00012     'CameraTopV4RotY':2.09e-2,
00013     'CameraTopV4RotZ':0.0,
00014     }
00015 
00016 Nao_links = {
00017     u'Torso_link':'torso',
00018     u'HeadYaw_link':'Neck',
00019     u'HeadPitch_link':'Head',
00020     u'LShoulderPitch_link':'LShoulder',
00021     u'RShoulderPitch_link':'RShoulder',
00022     u'LShoulderRoll_link':'LBicep',
00023     u'RShoulderRoll_link':'RBicep',
00024     u'LElbowYaw_link':'LElbow',
00025     u'RElbowYaw_link':'RElbow',
00026     u'LElbowRoll_link':'LForeArm',
00027     u'RElbowRoll_link':'RForeArm',
00028     u'LHipYawPitch_link':'LPelvis',
00029     u'RHipYawPitch_link':'RPelvis',
00030     u'LHipRoll_link':'LHip',
00031     u'RHipRoll_link':'RHip',
00032     u'LHipPitch_link':'LThigh',
00033     u'RHipPitch_link':'RThigh',
00034     u'LKneePitch_link':'LTibia',
00035     u'LAnklePitch_link':'LAnklePitch',
00036     u'RAnklePitch_link':'RAnklePitch',
00037     u'RKneePitch_link':'RTibia',
00038     u'LAnkleRoll_link':'l_ankle',
00039     u'RAnkleRoll_link':'r_ankle',
00040     u'LWristYaw_link':'l_wrist',
00041     u'RWristYaw_link':'r_wrist',
00042     u'LHand_actuator_frame':'l_gripper',
00043     u'RHand_actuator_frame':'r_gripper',
00044     u'LLeg_effector':'l_sole',
00045     u'RLeg_effector':'r_sole',
00046 
00047     #SENSORS
00048     'RFoot/FSR/FrontLeft_sensor':'RFsrFL_frame',
00049     'RFoot/FSR/RearLeft_sensor':'RFsrRL_frame',
00050     'RFoot/FSR/FrontRight_sensor':'RFsrFR_frame',
00051     'RFoot/FSR/RearRight_sensor':'RFsrRR_frame',
00052     'LFoot/FSR/FrontLeft_sensor':'LFsrFL_frame',
00053     'LFoot/FSR/RearLeft_sensor':'LFsrRL_frame',
00054     'LFoot/FSR/FrontRight_sensor':'LFsrFR_frame',
00055     'LFoot/FSR/RearRight_sensor':'LFsrRR_frame',
00056     'Sonar/Right_sensor':'RSonar_frame',
00057     'Sonar/Left_sensor':'LSonar_frame',
00058     'InfraredL_sensor':'LInfraRed_frame',
00059     'InfraredR_sensor':'RInfraRed_frame',
00060     'CameraTop_sensor':'CameraTop_frame',
00061     'CameraBottom_sensor':'CameraBottom_frame',
00062     'LFoot/Bumper/Left_sensor':'LFootBumperLeft_frame',
00063     'LFoot/Bumper/Right_sensor':'LFootBumperRight_frame',
00064     'RFoot/Bumper/Left_sensor':'RFootBumperLeft_frame',
00065     'RFoot/Bumper/Right_sensor':'RFootBumperRight_frame',
00066     'ChestBoard/Button_sensor':'ChestButton_frame',
00067     'Head/Touch/Front_sensor':'HeadTouchFront_frame',
00068     'Head/Touch/Middle_sensor':'HeadTouchMiddle_frame',
00069     'Head/Touch/Rear_sensor':'HeadTouchRear_frame',
00070     'LHand/Touch/Left_sensor':'LHandTouchLeft_frame',
00071     'LHand/Touch/Back_sensor':'LHandTouchBack_frame',
00072     'LHand/Touch/Right_sensor':'LHandTouchRight_frame',
00073     'RHand/Touch/Left_sensor':'RHandTouchLeft_frame',
00074     'RHand/Touch/Back_sensor':'RHandTouchBack_frame',
00075     'RHand/Touch/Right_sensor':'RHandTouchRight_frame',
00076     'Accelerometer_sensor':'ImuTorsoAccelerometer_frame',
00077     'Gyrometer_sensor':'ImuTorsoGyrometer_frame',
00078     'MicroFront_sensor':'MicroFrontCenter_frame',
00079     'MicroRear_sensor':'MicroRearCenter_frame',
00080     'MicroLeft_sensor':'MicroSurroundLeft_frame',
00081     'MicroRight_sensor':'MicroSurroundRight_frame',
00082     }
00083 
00084 Nao_visu = {
00085     u'Torso_link': ur.Cylinder(0.015,0.2115),
00086     u'HeadPitch_link':ur.Cylinder(0.04,0.14),
00087     u'LShoulderRoll_link':ur.Cylinder(0.015,0.09),
00088     u'LElbowRoll_link': ur.Cylinder(0.015,0.05065),
00089     u'LHipPitch_link': ur.Cylinder(0.015,0.1),
00090     u'LKneePitch_link':   ur.Cylinder(0.015,0.1),
00091     u'RHipPitch_link': ur.Cylinder(0.015,0.1),
00092     u'RKneePitch_link': ur.Cylinder(0.015,0.1),
00093     u'RShoulderRoll_link': ur.Cylinder(0.015,0.09),
00094     u'RElbowRoll_link':  ur.Cylinder(0.015,0.05065),
00095     u'LAnkleRoll_link': ur.Box((0.16,0.06,0.015)),
00096     u'RAnkleRoll_link': ur.Box((0.16,0.06,0.015)),
00097     u'LWristYaw_link':  ur.Cylinder(0.015,0.058),
00098     u'RWristYaw_link':  ur.Cylinder(0.015,0.058),
00099     }
00100 
00101 Nao_orig=  {
00102     u'Torso_link': ur.Pose((0,0,0.02075),(0,0,0)),
00103     u'HeadPitch_link':  ur.Pose((0,0,0.058),(pi_2,0,0)),
00104     u'LShoulderRoll_link':  ur.Pose((0.045,0,0),(pi_2,0,pi_2)),
00105     u'LElbowRoll_link': ur.Pose((0.025325,0,0),(pi_2,0,pi_2)),
00106     u'LHipPitch_link':   ur.Pose((0,0,-0.05),(0,0,0)),
00107     u'LKneePitch_link':  ur.Pose((0,0,-0.05),(0,0,0)),
00108     u'RHipPitch_link':   ur.Pose((0,0,-0.05),(0,0,0)),
00109     u'RKneePitch_link': ur.Pose((0,0,-0.05),(0,0,0)),
00110     u'RShoulderRoll_link': ur.Pose((0.045,0,0),(pi_2,0,pi_2)),
00111     u'RElbowRoll_link': ur.Pose((0.025325,0,0),(pi_2,0,pi_2)),
00112     u'LAnkleRoll_link': ur.Pose((0.02,0,0.0075),(0,0,0)),
00113     u'RAnkleRoll_link': ur.Pose((0.02,0,0.0075),(0,0,0)),
00114     u'LWristYaw_link': ur.Pose((0.029,0,0),(pi_2,0,pi_2)),
00115     u'RWristYaw_link': ur.Pose((0.029,0,0),(pi_2,0,pi_2)),
00116     }
00117 


naoqi_tools
Author(s): Mikael Arguedas
autogenerated on Thu Aug 27 2015 14:05:48