Arm Type Robots - ETS¶
Code author: Jesse Haviland
ETS¶
Created on Tue Apr 24 15:48:52 2020 @author: Jesse Haviland
-
class
ropy.robot.ETS.
ETS
(elinks, name='noname', base_link=None, ee_link=None, manufacturer='', base=None, tool=None, gravity=array([0.0, 0.0, 9.81]))[source]¶ Bases:
object
The Elementary Transform Sequence (ETS). A superclass which represents the kinematics of a serial-link manipulator
- Parameters
et_list (ET list) – List of elementary transforms which represent the robot kinematics
name (str, optional) – Name of the robot
manufacturer (str, optional) – Manufacturer of the robot
base (SE3, optional) – Location of the base is the world frame
tool (SE3, optional) – Offset of the flange of the robot to the end-effector
gravity – The gravity vector
- References
Kinematic Derivatives using the Elementary Transform Sequence, J. Haviland and P. Corke
-
property
qlim
¶
-
property
ets
¶
-
property
n
¶
-
property
M
¶
-
property
q_idx
¶
-
property
name
¶
-
property
manuf
¶
-
property
gravity
¶
-
property
q
¶
-
property
qd
¶
-
property
qdd
¶
-
property
control_type
¶
-
property
base
¶
-
property
tool
¶
-
property
base_link
¶
-
property
ee_link
¶
-
fkine
(q=None)[source]¶ Evaluates the forward kinematics of a robot based on its ETS and joint angles q.
T = fkine(q) evaluates forward kinematics for the robot at joint configuration q.
T = fkine() as above except uses the stored q value of the robot object.
Trajectory operation: Calculates fkine for each point on a trajectory of joints q where q is (nxm) and the returning SE3 in (m)
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
- Returns
The transformation matrix representing the pose of the end-effector
- Return type
SE3
- Notes
The robot’s base or tool transform, if present, are incorporated into the result.
- References
Kinematic Derivatives using the Elementary Transform Sequence, J. Haviland and P. Corke
-
allfkine
(q=None)[source]¶ Tall = allfkine(q) evaluates fkine for each joint within a robot and returns a trajecotry of poses.
Tall = allfkine() as above except uses the stored q value of the robot object.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
- Return T
Homogeneous transformation trajectory
- Rtype T
SE3 list
- Notes
The robot’s base transform, if present, are incorporated into the result.
- References
Kinematic Derivatives using the Elementary Transform Sequence, J. Haviland and P. Corke
-
jacob0
(q=None)[source]¶ J0 = jacob0(q) is the manipulator Jacobian matrix which maps joint velocity to end-effector spatial velocity. v = J0*qd in the base frame.
J0 = jacob0() as above except uses the stored q value of the robot object.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
- Return J
The manipulator Jacobian in ee frame
- Return type
float ndarray(6,n)
- References
Kinematic Derivatives using the Elementary Transform Sequence, J. Haviland and P. Corke
-
jacobe
(q=None)[source]¶ Je = jacobe(q) is the manipulator Jacobian matrix which maps joint velocity to end-effector spatial velocity. v = Je*qd in the end-effector frame.
Je = jacobe() as above except uses the stored q value of the robot object.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
- Return J
The manipulator Jacobian in ee frame
- Return type
float ndarray(6,n)
-
hessian0
(q=None, J0=None)[source]¶ The manipulator Hessian tensor maps joint acceleration to end-effector spatial acceleration, expressed in the world-coordinate frame. This function calulcates this based on the ETS of the robot. One of J0 or q is required. Supply J0 if already calculated to save computation time
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
J0 (float ndarray(6,n)) – The manipulator Jacobian in the 0 frame
- Returns
The manipulator Hessian in 0 frame
- Return type
float ndarray(6,n,n)
- References
Kinematic Derivatives using the Elementary Transform Sequence, J. Haviland and P. Corke
-
manipulability
(q=None, J=None)[source]¶ Calculates the manipulability index (scalar) robot at the joint configuration q. It indicates dexterity, that is, how isotropic the robot’s motion is with respect to the 6 degrees of Cartesian motion. The measure is high when the manipulator is capable of equal motion in all directions and low when the manipulator is close to a singularity. One of J or q is required. Supply J if already calculated to save computation time
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
J (float ndarray(6,n)) – The manipulator Jacobian in any frame
- Returns
The manipulability index
- Return type
float
- References
Analysis and control of robot manipulators with redundancy, T. Yoshikawa,
Robotics Research: The First International Symposium (M. Brady and R. Paul, eds.), pp. 735-747, The MIT press, 1984.
-
jacobm
(q=None, J=None, H=None)[source]¶ Calculates the manipulability Jacobian. This measure relates the rate of change of the manipulability to the joint velocities of the robot. One of J or q is required. Supply J and H if already calculated to save computation time
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
J (float ndarray(6,n)) – The manipulator Jacobian in any frame
H (float ndarray(6,n,n)) – The manipulator Hessian in any frame
- Returns
The manipulability Jacobian
- Return type
float ndarray(n)
- References
Kinematic Derivatives using the Elementary Transform Sequence, J. Haviland and P. Corke
-
jacobev
(q=None)[source]¶ Jv = jacobev(q) is the spatial velocity Jacobian, at joint configuration q, which relates the velocity in the base frame to the velocity in the end-effector frame.
Jv = jacobev() as above except uses the stored q value of the robot object.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
- Returns J
The velocity Jacobian in ee frame
- Rtype J
float ndarray(6,6)
-
jacob0v
(q=None)[source]¶ Jv = jacob0v(q) is the spatial velocity Jacobian, at joint configuration q, which relates the velocity in the end-effector frame to velocity in the base frame
Jv = jacob0v() as above except uses the stored q value of the robot object.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
- Returns J
The velocity Jacobian in 0 frame
- Rtype J
float ndarray(6,6)
ET¶
@author: Jesse Haviland
-
class
ropy.robot.ET.
ET
(axis_func, axis, eta=None, joint=None)[source]¶ Bases:
object
This class implements a single elementary transform (ET)
- Parameters
axis_func (static et.T__ function) – The function which calculates the transform of the ET.
eta (float, optional) – The coordinate of the ET. If not supplied the ET corresponds to a variable ET which is a joint
joint (int, optional) – If this ET corresponds to a joint, this corresponds to the joint number within the robot
- References
Kinematic Derivatives using the Elementary Transform Sequence, J. Haviland and P. Corke
-
property
eta
¶
-
property
eta_deg
¶
-
property
axis_func
¶
-
property
axis
¶
-
property
jtype
¶
-
property
j
¶
-
T
(q=None)[source]¶ Calculates the transformation matrix of the ET
- Parameters
q (float (radians), required for variable ET's) – Is used if this ET is variable (a joint)
- Returns
The transformation matrix of the ET
- Return type
SE3
-
classmethod
TRx
(eta=None)[source]¶ An elementary transform (ET). A pure rotation of eta about the x-axis.
L = TRx(eta) will instantiate an ET object which represents a pure rotation about the x-axis by amount eta.
L = TRx() as above except this ET representation a variable rotation, i.e. a joint
- Parameters
eta (float (radians)) – The amount of rotation about the x-axis
joint (int) – The joint number within the robot
- Returns
An ET object
- Return type
-
classmethod
TRy
(eta=None)[source]¶ An elementary transform (ET). A pure rotation of eta about the y-axis.
L = TRy(eta) will instantiate an ET object which represents a pure rotation about the y-axis by amount eta.
L = TRy() as above except this ET representation a variable rotation, i.e. a joint
- Parameters
eta (float (radians)) – The amount of rotation about the y-axis
joint (int) – The joint number within the robot
- Returns
An ET object
- Return type
-
classmethod
TRz
(eta=None)[source]¶ An elementary transform (ET). A pure rotation of eta about the z-axis.
L = TRz(eta) will instantiate an ET object which represents a pure rotation about the z-axis by amount eta.
L = TRz() as above except this ET representation a variable rotation, i.e. a joint
- Parameters
eta (float (radians)) – The amount of rotation about the z-axis
- Returns
An ET object
- Return type
-
classmethod
Ttx
(eta=None)[source]¶ An elementary transform (ET). A pure translation of eta along the x-axis
L = Ttx(eta) will instantiate an ET object which represents a pure translation along the x-axis by amount eta.
L = Ttx() as above except this ET representation a variable translation, i.e. a joint
- Parameters
eta (float (metres)) – The amount of translation along the x-axis
- Returns
An ET object
- Return type
-
classmethod
Tty
(eta=None)[source]¶ An elementary transform (ET). A pure translation of eta along the x-axis
L = Tty(eta) will instantiate an ET object which represents a pure translation along the y-axis by amount eta.
L = Tty() as above except this ET representation a variable translation, i.e. a joint
- Parameters
eta (float (metres)) – The amount of translation along the x-axis
- Returns
An ET object
- Return type
-
classmethod
Ttz
(eta=None)[source]¶ An elementary transform (ET). A pure translation of eta along the z-axis
L = Ttz(eta) will instantiate an ET object which represents a pure translation along the z-axis by amount eta.
L = Ttz() as above except this ET representation a variable translation, i.e. a joint
- Parameters
eta (float (metres)) – The amount of translation along the x-axis
- Returns
An ET object
- Return type