OpTaS  1.0.7
An optimization-based task specification library for trajectory optimization and model predictive control.
Classes | Functions | Variables
optas.spatialmath Namespace Reference

This is a partial port to Python/CasADi, with some modifications and additions, of the Spatial Math Toolbox for MATLAB. More...

Classes

class  Quaternion
 Quaternion class. More...
 

Functions

Callable arrayify_args (Callable fun)
 Decorator that ensures all input arguments are casadi arrays (i.e. More...
 
cs.DM I3 ()
 3-by-3 identity matrix. More...
 
cs.DM I4 ()
 4-by-4 identity matrix. More...
 
CasADiArrayType angvec2r (ArrayType theta, ArrayType v)
 Convert angle and vector orientation to a rotation matrix. More...
 
CasADiArrayType r2t (ArrayType R)
 Convert rotation matrix to a homogeneous transform. More...
 
CasADiArrayType rotx (ArrayType theta)
 SO(3) rotation about X axis. More...
 
CasADiArrayType roty (ArrayType theta)
 SO(3) rotation about Y axis. More...
 
CasADiArrayType rotz (ArrayType theta)
 SO(3) rotation about Z axis. More...
 
CasADiArrayType rpy2r (ArrayType rpy, str opt="zyx")
 Roll-pitch-yaw angles to SO(3) rotation matrix. More...
 
CasADiArrayType rt2tr (ArrayType R, ArrayType t)
 Convert rotation and translation to homogeneous transform. More...
 
CasADiArrayType skew (ArrayType v)
 Create skew-symmetric matrix. More...
 
CasADiArrayType t2r (ArrayType T)
 Rotational submatrix. More...
 
CasADiArrayType invt (ArrayType T)
 Inverse of a homogeneous transformation matrix. More...
 
CasADiArrayType transl (ArrayType T)
 SE(3) translational homogeneous transform. More...
 
CasADiArrayType unit (ArrayType v)
 Unitize a vector. More...
 

Variables

 ArrayType = Union[cs.DM, cs.SX, List[float], Tuple[float], cs.np.ndarray, float, int]
 Accepted array types. More...
 
 CasADiArrayType = Union[cs.DM, cs.SX]
 CasADi array types typically returned by OpTaS methods. More...
 
 pi = cs.np.pi
 The number pi (i.e. More...
 
 eps = cs.np.finfo(float).eps
 The machine epsilon. More...
 

Detailed Description

This is a partial port to Python/CasADi, with some modifications and additions, of the Spatial Math Toolbox for MATLAB.

See the following. https://github.com/petercorke/spatialmath-matlab

Function Documentation

◆ angvec2r()

CasADiArrayType optas.spatialmath.angvec2r ( ArrayType  theta,
ArrayType  v 
)

Convert angle and vector orientation to a rotation matrix.

This method uses Rodrigue's formula.

Parameters
thetaAngle of rotation (radians).
vDirection vector to rotate about.
Returns
Rotation matrix.

◆ arrayify_args()

Callable optas.spatialmath.arrayify_args ( Callable  fun)

Decorator that ensures all input arguments are casadi arrays (i.e.

either DM or SX).

Parameters
funCallable function
Returns
Wrapper that ensures the input to the given function are casadi arrays.

◆ I3()

cs.DM optas.spatialmath.I3 ( )

3-by-3 identity matrix.

Returns
Identity matrix of order 3.

◆ I4()

cs.DM optas.spatialmath.I4 ( )

4-by-4 identity matrix.

Returns
Identity matrix of order 4.

◆ invt()

CasADiArrayType optas.spatialmath.invt ( ArrayType  T)

Inverse of a homogeneous transformation matrix.

Parameters
THomogeneous transformation matrix.
Returns
Homogeneous transformation matrix such that Tinv @ T = I where I is the identity.

◆ r2t()

CasADiArrayType optas.spatialmath.r2t ( ArrayType  R)

Convert rotation matrix to a homogeneous transform.

Parameters
RA 3-by-3 rotation matrix.
Returns
Homogenous transformation with given rotation and zero translation.

◆ rotx()

CasADiArrayType optas.spatialmath.rotx ( ArrayType  theta)

SO(3) rotation about X axis.

Parameters
thetaAngle of rotation (radians).
Returns
A 3-by-3 rotation matrix.

◆ roty()

CasADiArrayType optas.spatialmath.roty ( ArrayType  theta)

SO(3) rotation about Y axis.

Parameters
thetaAngle of rotation (radians).
Returns
A 3-by-3 rotation matrix.

◆ rotz()

CasADiArrayType optas.spatialmath.rotz ( ArrayType  theta)

SO(3) rotation about Z axis.

Parameters
thetaAngle of rotation (radians).
Returns
A 3-by-3 rotation matrix.

◆ rpy2r()

CasADiArrayType optas.spatialmath.rpy2r ( ArrayType  rpy,
str   opt = "zyx" 
)

Roll-pitch-yaw angles to SO(3) rotation matrix.

Parameters
rpyRoll-Pitch-Yaw angles in radians.
optOrder option. Acceptable inputs:
  • 'xyz' Rotations about X, Y, Z axes (for a robot gripper)
  • 'zyx' Rotations about Z, Y, X axes (for a mobile robot, default)
  • 'yxz' Rotations about Y, X, Z axes (for a camera)
  • 'arm' Rotations about X, Y, Z axes (for a robot arm)
  • 'vehicle' Rotations about Z, Y, X axes (for a mobile robot)
  • 'camera' Rotations about Y, X, Z axes (for a camera)
Returns
A 3-by-3 rotation matrix.

◆ rt2tr()

CasADiArrayType optas.spatialmath.rt2tr ( ArrayType  R,
ArrayType  t 
)

Convert rotation and translation to homogeneous transform.

Parameters
RA 3-by-3 rotation matrix.
tA vector with 3 elements.
Returns
Homogeneous transformation matrix.

◆ skew()

CasADiArrayType optas.spatialmath.skew ( ArrayType  v)

Create skew-symmetric matrix.

If V (1x1) then (order 2) S =

  | 0  -v |
  | v   0 |

and if V (1x3) then (order 3) S =

  |  0  -vz   vy |
  | vz    0  -vx |
  |-vy   vx    0 |
Parameters
vThe form of the skew-symmetric matrix, either a scalar or vector with 3 elements.
Returns
Skew-symmetric matrix of order 2 or 3.

◆ t2r()

CasADiArrayType optas.spatialmath.t2r ( ArrayType  T)

Rotational submatrix.

Parameters
Homogenoustransformation matrix.
Returns
A 3-by-3 rotation matrix.

◆ transl()

CasADiArrayType optas.spatialmath.transl ( ArrayType  T)

SE(3) translational homogeneous transform.

Parameters
THomogeneous transformation matrix.
Returns
Translation part of the homogeneous transformation.

◆ unit()

CasADiArrayType optas.spatialmath.unit ( ArrayType  v)

Unitize a vector.

Parameters
vA vector of order 3.
Returns
A vector of order 3 with unit magnitude that is parralel to input vector.

Variable Documentation

◆ ArrayType

optas.spatialmath.ArrayType = Union[cs.DM, cs.SX, List[float], Tuple[float], cs.np.ndarray, float, int]

Accepted array types.

◆ CasADiArrayType

optas.spatialmath.CasADiArrayType = Union[cs.DM, cs.SX]

CasADi array types typically returned by OpTaS methods.

◆ eps

optas.spatialmath.eps = cs.np.finfo(float).eps

The machine epsilon.

◆ pi

optas.spatialmath.pi = cs.np.pi

The number pi (i.e.

3.141...).