simple_robot_control::arm::Arm Class Reference

List of all members.

Public Member Functions

def __init__
def getIK
def getJointAngles
def getJointNames
def getState
def goToAngle
def goToPose
def goToPosition
def gripperToWrist
def makePose
def moveGripperToPose
def rotateWrist
def sendTraj

Public Attributes

 cAngles
 controller
 ikPath
 joint_names
 runIK
 side
 trajClient

Detailed Description

Definition at line 58 of file arm.py.


Member Function Documentation

def simple_robot_control::arm::Arm::__init__ (   self,
  side 
)

Definition at line 59 of file arm.py.

def simple_robot_control::arm::Arm::getIK (   self,
  goalPose,
  link_name,
  seedAngles 
)
Calls inverse kinematics service for the arm. 
    goalPose -  Pose Stamped message showing desired position of link in coord system
    linkName - goal Pose target link name -  (r_wrist_roll_link or l_wrist_roll_link)
    startAngles -  seed angles for IK

Definition at line 104 of file arm.py.

def simple_robot_control::arm::Arm::getJointAngles (   self  ) 

Definition at line 97 of file arm.py.

def simple_robot_control::arm::Arm::getJointNames (   self  ) 
Contacts param server to get controller joints 

Definition at line 93 of file arm.py.

def simple_robot_control::arm::Arm::getState (   self  ) 
Returns the current state of action client 

Definition at line 89 of file arm.py.

def simple_robot_control::arm::Arm::goToAngle (   self,
  angles,
  time,
  wait = True 
)
This method moves the arm to the specified joint angles. Users must make
    sure to obey safe joint limits.

Definition at line 120 of file arm.py.

def simple_robot_control::arm::Arm::goToPose (   self,
  pos,
  orientation,
  frame_id,
  time,
  wait = True,
  seed_angles = False 
)
This method uses getIK to move the x_wrist_roll_link to the 
    specific point and orientation specified in frame_id's coordinates. 
    Time specifies the duration of the planned trajectory, 
    wait whether to block or not. 

Definition at line 173 of file arm.py.

def simple_robot_control::arm::Arm::goToPosition (   self,
  pos,
  frame_id,
  time,
  wait = True 
)
This method uses getIK to move the x_wrist_roll_link to the 
    specific pos specified in frame_id's coordinates. Time specifies
    the duration of the planned trajectory, wait whether to block or not. 

Definition at line 166 of file arm.py.

def simple_robot_control::arm::Arm::gripperToWrist (   self,
  pos,
  orientation 
)

Definition at line 193 of file arm.py.

def simple_robot_control::arm::Arm::makePose (   self,
  xyz,
  orientation,
  frameID 
)
This is a shortcut method for making pose stamped messages

Definition at line 200 of file arm.py.

def simple_robot_control::arm::Arm::moveGripperToPose (   self,
  pos,
  orientation,
  frame_id,
  time,
  wait = True 
)
This method uses gripperToWrist() to calculate the pos_new of the wrist
    so that the gripper is moved to the given pos and orientation.

Definition at line 186 of file arm.py.

def simple_robot_control::arm::Arm::rotateWrist (   self,
  angle,
  speed = 2.0,
  wait = True,
  velocity = 0.0 
)
Rotates wrist by angle in radians. speed is the amount of time that it would take for one revolution.
    Velocity sets explicit speed to be attained  - careful! If velocity is to high, the wrist may rotate in
    opposite direction first

Definition at line 138 of file arm.py.

def simple_robot_control::arm::Arm::sendTraj (   self,
  traj,
  wait = True 
)
Send the joint trajectory goal to the action server 

Definition at line 82 of file arm.py.


Member Data Documentation

Definition at line 78 of file arm.py.

Definition at line 70 of file arm.py.

Definition at line 62 of file arm.py.

Definition at line 77 of file arm.py.

Definition at line 80 of file arm.py.

Definition at line 61 of file arm.py.

Definition at line 71 of file arm.py.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


simple_robot_control
Author(s): Christian Bersch, Sebastian Haug
autogenerated on Fri Jan 11 10:10:10 2013