MAGIKS  1.1
Manipulator General Inverse Kinematic Solver
 All Classes Namespaces Files Functions Variables Pages
Public Member Functions | Public Attributes | List of all members
PR2 Class Reference

Contains properties and methods managing the kinematics of the PR2 robot. More...

Inheritance diagram for PR2:

Public Member Functions

def __init__
 The Class Constructor: More...
 
def joint_in_range
 Use this function to check if a given value for specific joint is in its feasibility range. More...
 
def all_joints_in_range
 Use this function to check if all values of the given joint vector are in their feasibility range. More...
 
def full_config
 Dumps the given partial joint values in the given full set of PR2 joints and returns the modified full set of joints This function does change object configuration. More...
 
def set_ofuncode
 protected More...
 
def objective_function
 Use this function to find the current value of the objective function. More...
 
def set_config
 Sets the robot configuration to the desired given joint values. More...
 
def set_target
 Sets the endeffector target to a desired position and orientation. More...
 
def set_posture
 
def all_IK_solutions
 Finds all the feasible solutions of the Inverse Kinematic problem for given redundant parameter vector \( \phi \). More...
 
def objective_function_for
 Use this function to get the value of the objective function for a given configuration q Why has this function been written? Sometimes you want to find the value of the objective function for a configuration but you don't want to set that configuration (you don't want to take the manipulator to that configuration) In this case, you can not use function "self.objective_function()" which gives the value of the objective function for the current configuration of the robot. More...
 
def IK_config
 Finds the solution of the Inverse Kinematic problem for given redundant parameter vector \( phi \) in free-base mode. More...
 
def pos_rarm_grip_wrt_tor_shpan
 Use this function to get the current position of the right gripper (Arm Endeffector) w.r.t the arm base. More...
 
def pos_larm_grip_wrt_tor_shpan
 Use this function to get the current position of the left gripper (Arm Endeffector) w.r.t the arm base. More...
 
def pos_larm_grip_wrt_tor
 Use this function to get the current position of the left gripper (Arm Endeffector) w.r.t the torso. More...
 
def pos_rarm_grip_wrt_tor
 Use this function to get the current position of the right gripper (Arm Endeffector) w.r.t the torso. More...
 
def pos_rarm_grip
 Use this function to get the current global position of the right gripper (Arm Endeffector). More...
 
def pos_larm_grip
 Use this function to get the current global position of the left gripper (Arm Endeffector). More...
 
def rarm_end_position
 Returns the current position of the endeffector or gripper end for the right arm. More...
 
def larm_end_position
 Returns the current position of the endeffector or gripper end for the left arm. More...
 
def end_position
 Returns the current position of the endeffector or gripper end for the reference arm. More...
 
def rarm_end_orientation
 
def larm_end_orientation
 
def end_orientation
 
def div_theta_err
 
def redundant_parameters
 Use this function to get the current values of the five redundant parameters of the PR2 robot in free-base mode. More...
 
def div_phi_err
 
def redundancy_jacobian
 
def redundancy_jacobian_extended
 
def div_theta_ofun
 
def div_phi_ofun
 
def joint_stepsize_interval
 
def optimum_joint_stepsize
 
def steepest_descent_redundancy_correction
 
def endeffector_in_target
 
def optimize_config
 
def extended_config
 
def goto_target
 
def project_to_js
 
def project_to_ts
 

Public Attributes

 ql
 A numpy vector of size 7 containing the lower bounds of the arm joints. More...
 
 qh
 A numpy vector of size 7 containing the upper bounds of the arm joints. More...
 
 qm
 A numpy vector of size 18 containing a set of reference values for the joints. More...
 
 q
 A numpy vector of size 18 containing the current values of the joints. More...
 
 ofuncode
 Specifies the objective function for redundancy optimization. More...
 
 W
 
 rarm
 An instance of class packages.nima.robotics.kinematics.special_geometries.pr2.pr2_arm_kinematics.PR2_ARM() containing the kinematic properties and methods of the right arm. More...
 
 larm
 An instance of class packages.nima.robotics.kinematics.special_geometries.pr2.pr2_arm_kinematics.PR2_ARM() containing the kinematic properties and methods of the left arm. More...
 
 d7
 
 b0
 
 l0
 
 p_EFR_WR
 
 p_EFL_WL
 
 control_mode
 
 larm_reference
 A boolean specifying the reference arm for the endeffector. More...
 
 xd
 A numpy vector of size 3 representing the desired position of the Endeffector. More...
 
 Rd
 A \( 3 \times 3 \) rotation matrix specifying the desired endeffector orientation for the IK problem. More...
 
 ofun_computed
 
 div_theta_ofun_updated
 
 div_phi_ofun_updated
 
 ofun
 
 C
 
 S
 
 p_BO
 
 p_BL_BO
 
 p_BR_BO
 
 R_B
 
 p_EFR
 
 p_EFL
 
 R_WR
 
 R_WL
 
 redun_jacob_updated
 
 redun_jacob_ext_updated
 
 geometric_jacob_updated
 
 div_theta_err_updated
 
 redundant_parameters_updated
 
 p_WR_BR
 
 p_WL_BL
 
 R_WR_B
 
 R_WL_B
 
 E
 
 F
 
 phi
 
 RJ
 
 ERJ
 
 DTG
 
 DFG
 
 in_target
 

Detailed Description

Contains properties and methods managing the kinematics of the PR2 robot.

This class contains all properties and methods required for forward and inverse kinematic computations and kinematic control of the PR2 robot in two control modes: Fixed-Base and Free-Base In fixed-base mode, the body of the robot is assumed fixed (No navigation) and only the arms can move while in free-base mode, the robot trunk is free to navigate. Each control mode can be set for one of the arms as the reference arm (Endeffector) Dual arm control (two endeffectors) is not supported in this version PR2 has 18 degrees of freedom. The Robot will have two arms that each of them contains its associated joint values in its config property.

Definition at line 56 of file pr2_kinematics.py.

Constructor & Destructor Documentation

def __init__ (   self,
  a0 = 0.1,
  b0 = 0.05,
  d2 = 0.4,
  d4 = 0.321,
  d7 = 0.168,
  l0 = 0.188,
  ql = default_ql,
  qh = default_qh,
  run_magiks = False 
)

The Class Constructor:

Parameters
a0A float specifying the value of /f$ a_0 /f$ in the DH parameters of the arm
b0A float specifying the distance of line connecting the two arms from the center of robot base
d2A float specifying the value of /f$ d_2 /f$ in the DH parameters of the arm
d4A float specifying the value of /f$ d_4 /f$ in the DH parameters of the arm
d7A float specifying the length of the gripper
l0A float specifying half of the distance between the arms
qlA numpy vector of size 18 containing the lower bounds of the arm joints
qhA numpy vector of size 18 containing the upper bounds of the arm joints

Definition at line 66 of file pr2_kinematics.py.

Member Function Documentation

def all_IK_solutions (   self,
  phi 
)

Finds all the feasible solutions of the Inverse Kinematic problem for given redundant parameter vector \( \phi \).

Parameters
phiIs a numpy vector of five elements containing the values of five redundant parameters in free-base mode. The values of phi specify the following parameters:
phi[0] : The first joint angle q[0] (Shoulder-Pan joint angle)
phi[1] : The r cylindrical coordinate of the wrist (wrist joint center) position w.r.t. the arm base (shoulder-pan joint center) in torso coordinate system:

\[ r = p_x^2 + p_y^2 \]

where \( p_x \) and \( p_y \) are the x and y cartesian coordinates of the wrist position w.r.t. the arm base in torso coordinate system.
phi[2] : \( p_z \) or the z cartesian coordinate of the wrist position w.r.t. the arm base in torso coordinate system.
phi[3] : The \( \psi \) cylindrical coordinate of the wrist (wrist joint center) position w.r.t. the arm base in torso CS:

\[ \psi = \arctan( \frac {p_x} {p_y}) \]

( \( p_x \) and \( p_y \) can be determined from phi[1] and phi[3])
phi[4] : \( \tau \) or the rotation angle of the trunc base around z axis
Returns
An array of numpy vectors. Each numpy vector is a feasible solution and contains 11 elements. The first 7 elements are the arm joints(left arm if property larm_reference is True and right arm, otherwise) and the next 4 elements contain the values of non-arm degrees of freedom (q[7] to q[10]) This function only returns the feasible IK solutions but does NOT set the configuration so the joint values do not change The output will be None if given redundant parameters are invalid or out of feasible range.

Definition at line 370 of file pr2_kinematics.py.

def all_joints_in_range (   self,
  qd 
)

Use this function to check if all values of the given joint vector are in their feasibility range.

Parameters
qdA numpy vector of size 18 containing the values to be checked
Returns
A boolean: If The given joints "qd" are out of the range specified by properties: ql and qh, returns False, otherwise returns True
Example

Definition at line 167 of file pr2_kinematics.py.

def div_phi_err (   self)
Returns the divergence of the vector of kinematic constraints "e" in respect with the redundant parameters "phi"
It is a 9*5 matrix
f_ij = rond e_i / rond phi_j  (for i = 0,..,8 & j = 0,..,4) 
the value of "self.F" is computed in function "div_theta_e" to avoid repeated calculations

Definition at line 814 of file pr2_kinematics.py.

def div_phi_ofun (   self)
Returns the divergence of the objective function in respect with the redundant parameters "phi"
argument "ofun" specifies the code of the objective function which is set to 0 by default. 
The code legend is like function "div_theta_ofun" 

Definition at line 947 of file pr2_kinematics.py.

def div_theta_err (   self)
Returns the divergence of the vector of kinematic constraints "e" in respect with the joints
It is a 9*9 matrix
e_ij = rond e_i / rond q_j  (for i,j = 0,..,8)   

Definition at line 655 of file pr2_kinematics.py.

def div_theta_ofun (   self)
Returns the divergence of the objective function in respect with the joint angles
argument "ofun" specifies the code of the objective function which is set to 0 by default 

Definition at line 935 of file pr2_kinematics.py.

def end_orientation (   self,
  relative = True 
)

Definition at line 649 of file pr2_kinematics.py.

def end_position (   self,
  relative = None 
)

Returns the current position of the endeffector or gripper end for the reference arm.

Parameters
relativeA boolean: If True, the gripper position is returned w.r.t. the base (torso), otherwise, w.r.t. the global coordinate system If relative is None (default value), it will be set to True if the current control mode is 'Fixed-Base' and False if otherwise
Returns
A numpy vector of size 3, containing the current position of the reference arm gripper endpoint.

Definition at line 614 of file pr2_kinematics.py.

def endeffector_in_target (   self)
Returns true is endeffector is in target

Definition at line 1027 of file pr2_kinematics.py.

def extended_config (   self,
  q 
)

Definition at line 1082 of file pr2_kinematics.py.

def full_config (   self,
  q_partial,
  q_full = None,
  is_left_arm = False 
)

Dumps the given partial joint values in the given full set of PR2 joints and returns the modified full set of joints This function does change object configuration.

Parameters
q_partialA numpy vector of size 7 or 11. If size is 7, it should contain arm joint values and if 11, it should have arm joint values plus four trunk location parameters: \( h_{ts} = q[7] , x = q[8], y = q[9], \theta = q[10] \)
q_fullA numpy vector of size 18 containing all joint values of PR2, if Null, current object configuration will be set
Returns
A numpy vector of size 18 containing the full configuration of PR2 embedded q_partial

Definition at line 185 of file pr2_kinematics.py.

def goto_target (   self)
Finds the inverse kinematic solution closest to the current configuration
The new joint angles will be set if all the kinematic equations are satisfied. 
All kinematic parameters will be updated.
THIS FUNCTION IS NOT COMPLETE AND i NEED TO WORK ON IT MORE ...

Definition at line 1091 of file pr2_kinematics.py.

def IK_config (   self,
  phi 
)

Finds the solution of the Inverse Kinematic problem for given redundant parameter vector \( phi \) in free-base mode.

In case of redundant solutions, the one corresponding to the lowest objective function is selected. Class property ofuncode specifies the objective function. legend for ofuncode:

  • ofuncode = 0 (Default) the solution closest to current joint angles will be selected
  • ofuncode = 1 the solution corresponding to the lowest midrange distance is selected This function does NOT set the configuration so the joints do not change
    Parameters
    phiA numpy vector of size 5 containing the values of the five redundant parameters
    Returns
    A numpy vector of size 5 containing the IK solution corresponding to the given redundant parameters and the lowest value of the objective function. The first 7 elements contain the joints of the reference arm and the last four, are the values of the non-arm joints.

Definition at line 493 of file pr2_kinematics.py.

def joint_in_range (   self,
  i,
  qi 
)

Use this function to check if a given value for specific joint is in its feasibility range.

Parameters
iAn integer between 0 to 17 specifying the joint number to be checked
qiA float parameter specifying the value for the i-th joint
Returns
A boolean: True if the given joint angle qi is in feasible range for the i-th joint (within the specified joint limits for that joint)
Example

Definition at line 145 of file pr2_kinematics.py.

def joint_stepsize_interval (   self,
  direction 
)
Returns an interval for the step size by which the joints are allowed to move in the given "direction"
"direction" is a "n X 1" vector and specifies the direction of motion in the jointspace. 

Definition at line 959 of file pr2_kinematics.py.

def larm_end_orientation (   self,
  relative = None 
)

Definition at line 635 of file pr2_kinematics.py.

def larm_end_position (   self,
  relative = None 
)

Returns the current position of the endeffector or gripper end for the left arm.

Parameters
relativeA boolean: If True, the gripper position is returned w.r.t. the base (torso), otherwise, w.r.t. the global coordinate system If relative is None (default value), it will be set to True if the current control mode is 'Fixed-Base' and False if otherwise
Returns
A numpy vector of size 3, containing the current position of the left arm gripper endpoint.

Definition at line 597 of file pr2_kinematics.py.

def objective_function (   self)

Use this function to find the current value of the objective function.

Parameters
None
Returns
An instance of type float containing the value of the objective function

Definition at line 229 of file pr2_kinematics.py.

def objective_function_for (   self,
  q 
)

Use this function to get the value of the objective function for a given configuration q Why has this function been written? Sometimes you want to find the value of the objective function for a configuration but you don't want to set that configuration (you don't want to take the manipulator to that configuration) In this case, you can not use function "self.objective_function()" which gives the value of the objective function for the current configuration of the robot.

Parameters
qA numpy vector of size 11 containing the joint values of the reference arm followed by the four non-arm joints
Returns
A float indicating the value of the objective function for the given q

Definition at line 465 of file pr2_kinematics.py.

def optimize_config (   self,
  silent = True 
)
Assuming the endeffector is in target,
this function changes the robot configuration without changing the endeffector pose
until the minimum possible value of objective function is achieved
Note:
This function is a procedure and does not return any thing. Running this function, changes the robot configuration. 
If the current tip pose is not in target, this function fails with an error

Definition at line 1034 of file pr2_kinematics.py.

def optimum_joint_stepsize (   self,
  direction,
  safety_factor = 0.99 
)
returns the optimum feasible step size that minimizes the objective function 
if the joints are constrained to move in the given "direction".
The "safety_factor" specifies how much we can approach to the borders of joint limits

Definition at line 982 of file pr2_kinematics.py.

def pos_larm_grip (   self)

Use this function to get the current global position of the left gripper (Arm Endeffector).

Parameters
None
Returns
A numpy vector of 3 elements containing the global cartesian coordiantes of the end of left arm gripper.

Definition at line 572 of file pr2_kinematics.py.

def pos_larm_grip_wrt_tor (   self)

Use this function to get the current position of the left gripper (Arm Endeffector) w.r.t the torso.

Parameters
None
Returns
A numpy vector of 3 elements containing the left arm gripper position vector (endeffector position) w.r.t. the torso at the origin Note: The torso origin is at the floor footprint (projection) of the middle point between the two shoulder pan joint centers.

Definition at line 546 of file pr2_kinematics.py.

def pos_larm_grip_wrt_tor_shpan (   self)

Use this function to get the current position of the left gripper (Arm Endeffector) w.r.t the arm base.

Parameters
None
Returns
A numpy vector of 3 elements containing the position of the left arm gripper (endeffector position) w.r.t. the torso shoulder pan joint center.

Definition at line 534 of file pr2_kinematics.py.

def pos_rarm_grip (   self)

Use this function to get the current global position of the right gripper (Arm Endeffector).

Parameters
None
Returns
A numpy vector of 3 elements containing the global cartesian coordiantes of the end of right arm gripper.

Definition at line 565 of file pr2_kinematics.py.

def pos_rarm_grip_wrt_tor (   self)

Use this function to get the current position of the right gripper (Arm Endeffector) w.r.t the torso.

Parameters
None
Returns
A numpy vector of 3 elements containing the right arm gripper position vector (endeffector position) w.r.t. the torso at the origin Note: The torso origin is at the floor footprint (projection) of the middle point between the two shoulder pan joint centers.

Definition at line 557 of file pr2_kinematics.py.

def pos_rarm_grip_wrt_tor_shpan (   self)

Use this function to get the current position of the right gripper (Arm Endeffector) w.r.t the arm base.

Parameters
None
Returns
A numpy vector of 3 elements containing the position of the right arm gripper w.r.t. the torso shoulder pan joint center.

Definition at line 524 of file pr2_kinematics.py.

def project_to_js (   self,
  pos_traj,
  ori_traj = None,
  phi_start = 0.0,
  phi_end = None,
  delta_phi = 0.1,
  relative = True 
)
projects the given taskspace pose trajectory into the jointspace 
The phase starts from phi_start and added by delta_phi in each step.
at any time, if a solution is not found, the process stops

Definition at line 1119 of file pr2_kinematics.py.

def project_to_ts (   self,
  js_traj,
  phi_start = 0.0,
  phi_end = None,
  delta_phi = 0.1 
)
projects the given jointspace trajectory into the taskspace
The phase starts from phi_start and added by delta_phi in each step.
if at any time the joint values are not feasible, the process is stopped.

Definition at line 1172 of file pr2_kinematics.py.

def rarm_end_orientation (   self,
  relative = None 
)

Definition at line 620 of file pr2_kinematics.py.

def rarm_end_position (   self,
  relative = None 
)

Returns the current position of the endeffector or gripper end for the right arm.

Parameters
relativeA boolean: If True, the gripper position is returned w.r.t. the base (torso), otherwise, w.r.t. the global coordinate system If relative is None (default value), it will be set to True if the current control mode is 'Fixed-Base' and False if otherwise
Returns
A numpy vector of size 3, containing the current position of the right arm gripper endpoint.

Definition at line 580 of file pr2_kinematics.py.

def redundancy_jacobian (   self)
Returns the redundancy jacobian
Redundancy Jacobian is the partial derivative of the joints in respect with redundant parameters
RJ is a 9*5 matrix because the first and the last joints (q[0] and q[10]) are themselves selected as the redundant parameters

Definition at line 825 of file pr2_kinematics.py.

def redundancy_jacobian_extended (   self)
returns the extended redundancy jacobian which is "11 x 5" matrix.
It is the redundancy jacobian with two rows inserted At its first and last rows. 
These rows are corresponding to the first and last joints (shoulder pan joint and base rotation angle).

Definition at line 919 of file pr2_kinematics.py.

def redundant_parameters (   self)

Use this function to get the current values of the five redundant parameters of the PR2 robot in free-base mode.

@return A numpy vector of 5 elements containing the redundant parameters phi according to the parametrization specified in <provide link>

phi[0] = The first arm joint angle (Shoulder Pan joint)
phi[1] = The "r" coordinate of the relative wrist position(in cylinderical coordinates) phi[1]^2 = px^2 + py^2
phi[2] = The "z" coordinate of the relative wrist position(in cylinderical coordinates) phi[2]   = pz
phi[3] = The "psi" coordinate of the relative wrist position(in cylinderical coordinates) phi[3] = arctan(x/y)
phi[4] = The rotation of the base. Same as "tau" or the 10th joint angle (phi[4] = q[10] = tau)

Definition at line 787 of file pr2_kinematics.py.

def set_config (   self,
  qd 
)

Sets the robot configuration to the desired given joint values.

Parameters
qdA numpy array of 7 elements containing the values of the given joints
Returns
A boolean: True if the given configuration is successfully set, False if the given configuration is not successfully set. (If False is returned, the configuration will not chenge)

Definition at line 239 of file pr2_kinematics.py.

def set_ofuncode (   self,
  new_ofuncode 
)

protected

Definition at line 215 of file pr2_kinematics.py.

def set_posture (   self,
  posture 
)

Definition at line 327 of file pr2_kinematics.py.

def set_target (   self,
  target_position,
  target_orientation 
)

Sets the endeffector target to a desired position and orientation.

The target must be specified for the end of gripper of the reference arm. If the object is in Fixed-Base mode, then the target should be given w.r.t. the base (torso). If the object is in Free-Base mode, then the target should be given w.r.t. the global(lab) frame.

Parameters
target_positionA numpy array of 3 elements specifying the desired endeffector position
target_orientationA \( 3 \times 3 \) numpy rotation matrix representing the desired endeffector orientation
Returns
A boolean: True if the given pose is successfully set, False if the given pose is not successfully set because of an error (If False is returned, properties self.xd and self.RD will not chenge)
sets the endeffector target to the given position and orientation
variables self.xd and self.Rd should not be manipulated by the user. Always use this function

Definition at line 291 of file pr2_kinematics.py.

def steepest_descent_redundancy_correction (   self)
Finds the steepest descent direction of the objective function for redundancy vector "phi"

Definition at line 1015 of file pr2_kinematics.py.

Member Data Documentation

b0

Definition at line 119 of file pr2_kinematics.py.

C

Definition at line 250 of file pr2_kinematics.py.

control_mode

Definition at line 127 of file pr2_kinematics.py.

d7

Definition at line 118 of file pr2_kinematics.py.

DFG

Definition at line 955 of file pr2_kinematics.py.

div_phi_ofun_updated

Definition at line 224 of file pr2_kinematics.py.

div_theta_err_updated

Definition at line 268 of file pr2_kinematics.py.

div_theta_ofun_updated

Definition at line 223 of file pr2_kinematics.py.

DTG

Definition at line 941 of file pr2_kinematics.py.

E

Definition at line 670 of file pr2_kinematics.py.

ERJ

Definition at line 926 of file pr2_kinematics.py.

F

Definition at line 671 of file pr2_kinematics.py.

geometric_jacob_updated

Definition at line 267 of file pr2_kinematics.py.

in_target

Definition at line 1031 of file pr2_kinematics.py.

l0

Definition at line 120 of file pr2_kinematics.py.

larm

An instance of class packages.nima.robotics.kinematics.special_geometries.pr2.pr2_arm_kinematics.PR2_ARM() containing the kinematic properties and methods of the left arm.

Definition at line 116 of file pr2_kinematics.py.

larm_reference

A boolean specifying the reference arm for the endeffector.

If True, the endeeffector is the end of left arm gripper, False if right arm

Definition at line 131 of file pr2_kinematics.py.

ofun

Definition at line 231 of file pr2_kinematics.py.

ofun_computed

Definition at line 222 of file pr2_kinematics.py.

ofuncode

Specifies the objective function for redundancy optimization.

this property should not be set by the user directly. Use method "self.set_ofuncode" to set this property code legend: 1: midrange distance 0: distance from current configuration

Definition at line 104 of file pr2_kinematics.py.

p_BL_BO

Definition at line 254 of file pr2_kinematics.py.

p_BO

Definition at line 253 of file pr2_kinematics.py.

p_BR_BO

Definition at line 255 of file pr2_kinematics.py.

p_EFL

Definition at line 262 of file pr2_kinematics.py.

p_EFL_WL

Definition at line 122 of file pr2_kinematics.py.

p_EFR

Definition at line 261 of file pr2_kinematics.py.

p_EFR_WR

Definition at line 121 of file pr2_kinematics.py.

p_WL_BL

Definition at line 606 of file pr2_kinematics.py.

p_WR_BR

Definition at line 589 of file pr2_kinematics.py.

phi

Definition at line 805 of file pr2_kinematics.py.

q

A numpy vector of size 18 containing the current values of the joints.

This property should not be manipulated by the user. Use method Set_Config() to change this property. The joints are in the following order: q[0] : Right Arm-Shoulder Pan Joint, q[1] : Right Arm-Shoulder Lift Joint, q[2] : Right Arm-Upper Arm Roll Joint, q[3] : Right Arm-Elbow Flex Joint, q[4] : Right Arm-Forearm Roll Joint, q[5] : Right Arm-Wrist Flex Joint, q[6] : Right Arm-Wrist Roll Joint, q[7] : "h_ts" the telescoping prismatic joint that lifts up and shifts down the trunk and arms, q[8] : "X_BO" the X position of the robot base, q[9] : "Y_BO" the Y position of the robot base, q[10] : "tau" the rotation angle of the robot base around "z" axis, q[11] to q[17] are designated for the left arm in the same order as the right arm

Definition at line 97 of file pr2_kinematics.py.

qh

A numpy vector of size 7 containing the upper bounds of the arm joints.

Definition at line 73 of file pr2_kinematics.py.

ql

A numpy vector of size 7 containing the lower bounds of the arm joints.

Definition at line 70 of file pr2_kinematics.py.

qm

A numpy vector of size 18 containing a set of reference values for the joints.

This parameter can be used as reference joint values for redundancy optimization. The redundancy will be used to set the joints as close as possible to these reference values. This property is by default set as the middle of joint ranges.

Definition at line 80 of file pr2_kinematics.py.

R_B

Definition at line 257 of file pr2_kinematics.py.

R_WL

Definition at line 264 of file pr2_kinematics.py.

R_WL_B

Definition at line 645 of file pr2_kinematics.py.

R_WR

Definition at line 263 of file pr2_kinematics.py.

R_WR_B

Definition at line 631 of file pr2_kinematics.py.

rarm

An instance of class packages.nima.robotics.kinematics.special_geometries.pr2.pr2_arm_kinematics.PR2_ARM() containing the kinematic properties and methods of the right arm.

Definition at line 112 of file pr2_kinematics.py.

Rd

A \( 3 \times 3 \) rotation matrix specifying the desired endeffector orientation for the IK problem.

Recommended not to be set directly. Always use function set_target() to change this property.

Definition at line 139 of file pr2_kinematics.py.

redun_jacob_ext_updated

Definition at line 266 of file pr2_kinematics.py.

redun_jacob_updated

Definition at line 265 of file pr2_kinematics.py.

redundant_parameters_updated

Definition at line 272 of file pr2_kinematics.py.

RJ

Definition at line 915 of file pr2_kinematics.py.

S

Definition at line 251 of file pr2_kinematics.py.

W

Definition at line 106 of file pr2_kinematics.py.

xd

A numpy vector of size 3 representing the desired position of the Endeffector.

Recommended to be used as a read only property. Use function set_target() to change the value of this property

Definition at line 135 of file pr2_kinematics.py.


The documentation for this class was generated from the following file: