Geometric Primitives

Vector

class PyKDL.Vector

The Vector class describes both a 3D vector and a 3D point in space. This class supports operators + - += -= on other vectors, and operators * / *= /= on doubles. The elements of the vector can be accessed using the [] operator from 0:2.

__init__()

Empty constructor defaults to 0, 0, 0

__init__(x, y, z)

Constructor with x, y, z

Parameters:
  • x (double) – x-component
  • y (double) – y-component
  • z (double) – z-component
Norm() → double

Return the norm of the vector

Normalize() → double

Normalize the vector in place, and return the norm of the vector

ReverseSign() → None

Reverses the sign of the vector

Zero() → None

Sets all elements in the vector to zero

x() → double

Return the x component of the vector

y() → double

Return the y component of the vector

z() → double

Return the z component of the vector

Static functions:

PyKDL.dot(v1, v2) → double

Returns the dot product of two vectors

Parameters:
  • v1 (Vector) – the first vector
  • v2 (Vector) – the second vector
operator*(v1, v2) -> Vector

Returns the cross producs of two vectors

Parameters:
  • v1 (Vector) – the first vector
  • v2 (Vector) – the second vector

Rotation

class PyKDL.Rotation

This class represents a 3D orientation in space. The internal representaion is a 3x3 rotation matrix. The elements of this matrix can be accessed using the [] operator with range 0:3, 0:3.

__init__()

Emtpy constructor defaults to identity rotation

__init__(Xx, Yx, Zx, Xy, Yy, Zy, Xz, Yz, Zz)

Constructor specifying rows of rotation matrix with 9 doubles

__init__(x, y, z)

Constructor specifying rows of rotation matrix with 3 Vectors

Parameters:
  • x (Vector) – the first row of the rotation matrix
  • y (Vector) – the second row of the rotation matrix
  • z (Vector) – the third row of the rotation matrix
DoRotX(angle) → None

Apply a rotation around the x-axis with angle

Parameters:angle (double) – the angle to rotate
DoRotY(angle) → None

Apply a rotation around the y-axis with angle

Parameters:angle (double) – the angle to rotate
DoRotZ(angle) → None

Apply a rotation around the z-axis with angle

Parameters:angle (double) – the angle to rotate
GetEulerZYX() -> (z, y, x)

Returns the z, y, x Euler angles that describe this rotation. First a rotation around the z-axis, then around the rotated y-axis, and finally around the rotated x-axis.

GetEulerZYZ() -> (z1, y, z2)

Returns the z, y, z Euler angles that describe this rotation. First a rotation around the z-axis, then around the rotated y-axis, and finally around the rotated z-axis.

GetQuaternion() -> (x, y, z, w)

Returns the x, y, z, w normalized quaternion that describes this rotation

GetRPY() -> (r, p, y)

Returns the r, p, y rotations around fixed axis that describe this rotation. First a rotation around the x-axis, then a rotation around the original y-axis, and finally a rotation around the original z-axis

GetRot() → axis

Returns a vector with the direction of the equivalent axis and its norm the angle. THis method returns the axis as a Vector

GetRotAngle() -> (angle, axis)

Returns the rotation angle around the equivalent axis. This method returns the angle as a double, and the rotation axis as a Vector

Inverse() → Rotation

Returns the inverse rotation (this is also the transpose of the rotation matrix)

Rot2() → None
SetInverse() → None
UnitX() → None
UnitY() → None
UnitZ() → None
operator*(Vector) -> Vector

Changes the reference frame of a Vector. The norm of the vector does not change.

operator*(Twist) -> Twist

Changes the refenrece frame of a Twist

operator*(Wrench) -> Wrench

Changes the refenrece frame of a Wrench

Static functions:

PyKDL.Identity() → Rotation

Constructs an identity rotation

PyKDL.Quaternion(x, y, z, w) → Rotation

Constructs a rotation from an x, y, z, w quaternion descripion

PyKDL.Rot(axis, angle) → Rotation

Constructs a rotation from a rotation of angle around axis

Parameters:
  • axis (Vector) – the axis to rotate around
  • angle (double) – the angle to rotate
PyKDL.RotX(angle) → Rotation

Constructs a rotation of angle around the x-axis

PyKDL.RotY(angle) → Rotation

Constructs a rotation of angle around the y-axis

PyKDL.RotZ(angle) → Rotation

Constructs a rotation of angle around the z-axis

PyKDL.EulerZYX(z, y, x) → Rotation

Constructs a rotation by first applying a rotation of z around the z-axis, then a rotation of y around the new y-axis, and finally a rotation of x around the new x-axis

PyKDL.EulerZYZ(z1, y, z2) → Rotation

Constructs a rotation by first applying a rotation or z1 around the z-axis, then a rotation of y around the new y-axis, and finally a rotation of z2 around the new z-axis

PyKDL.RPY(r, p, y) → Rotation

Constructs a rotation by first applying a rotation of r around the x-axis, then a rotation of p around the original y-axis, and finally a rotation of y around the original z-axis

Frame

class PyKDL.Frame
M

This is the Rotation of the frame

p

This is the Vector of the frame

__init__()

Construct an identity frame

__init__(rot, pos)

Construct a frame from a rotation and a vector

Parameters:
  • pos (Vector) – the position of the frame origin
  • rot (Rotation) – the rotation of the frame
__init__(pos)

Construct a frame from a vector, with identity rotation

Parameters:pos (Vector) – the position of the frame origin
__init__(rot)

Construct a frame from a rotation, with origin at 0, 0, 0

Parameters:rot (Rotation) – the rotation of the frame
Integrate(twist, frequency) → None

This frame is integrated into an updated frame with sample frequence, using first order integration

Parameters:
  • twist (Twist) – this twist is represented with respect to the current frame
  • frequency – the sample frequency to update this frame
Inverse() → Frame

Returns the inverse of the frame

operator*(Vector) -> Vector

Changes both the reference frame and the reference point of a Vector. Use this operator when the vector represents a point

operator*(Twist) -> Twist

Changes bothe the refenrece frame and the referece point of a Twist

operator*(Wrench) -> Wrench

Changes both the refenrece frame and the reference point of a Wrench

Static functions:

PyKDL.Identity() → Frame

Constructs an identity frame

PyKDL.HD(a, alpha, d, theta) → Frame

Constructs a transformationmatrix T_link(i-1)_link(i) with the Denavit-Hartenberg convention as described in the original publictation: Denavit, J. and Hartenberg, R. S., A kinematic notation for lower-pair mechanisms based on matrices, ASME Journal of Applied Mechanics, 23:215-221, 1955.

PyKDL.DH_Craig1989(a, alpha, d, theta) → Frame

Constructs a transformationmatrix T_link(i-1)_link(i) with the Denavit-Hartenberg convention as described in the Craigs book: Craig, J. J.,Introduction to Robotics: Mechanics and Control, Addison-Wesley, isbn:0-201-10326-5, 1986.

PyKDL.AddDelta(f, t, d) → Frame

Constructs a frame that is obtained by: starting from frame f, apply twist t, during time d

Parameters:
  • f (Frame) – the frame to start the integration from
  • t (Twist) – the twist to apply, represented in the same reference frame as f, and with reference point at the origin of f
  • d (double) – the duration to apply twist t
PyKDL.diff(f1, f2, d) → Twist

Returns the twist that is needed to move from frame f1 to frame f2 in a time d. The resulting twist is represented in the same reference frame as f1 and f2, and has reference point at the origin of f1

Parameters:
  • f1 (Frame) – the frame to start from
  • f2 (Frame) – the frame to end up in
  • d (double) – the duration to apply the resulting twist

Twist

class PyKDL.Twist
RefPoint() → None
ReverseSign() → None
Zero() → None
rot
vel

Wrench

class PyKDL.Wrench
RefPoint() → None
ReverseSign() → None
Zero() → None
force
torque

Table Of Contents

Previous topic

PyKDL

Next topic

Kinematic Chains

This Page