transf Class Reference

A rigid body transformation. More...

#include <matvec3D.h>

List of all members.

Public Member Functions

const mat3affine () const
transf inverse () const
void jacobian (double jac[])
 Creates a 6x6 jacobian from this transform.
bool operator!= (transf const &tr) const
transf const & operator= (transf const &tr)
bool operator== (transf const &tr) const
const Quaternionrotation () const
void set (const SoTransform *IVt)
void set (const mat3 &r, const vec3 &d)
void set (const Quaternion &r, const vec3 &d)
void tocol_Mat4 (col_Mat4 colTran) const
void toColMajorMatrix (double t[][4]) const
void toRowMajorMatrix (double t[][4]) const
void toSoTransform (SoTransform *IVt) const
 transf (const SoTransform *IVt)
 transf (const mat3 &r, const vec3 &d)
 transf (const Quaternion &r, const vec3 &d)
 transf ()
const vec3translation () const

Static Public Attributes

static const transf IDENTITY
 The Identity transform (1,0,0,0)[0,0,0].

Private Attributes

mat3 R
 A 3x3 matrix storing the current rotation.
Quaternion rot
 A 4x1 Quaternion storing the current rotation.
vec3 t
 A 3x1 vector storing the current translation.

Friends

transf coordinate_transf (const position &origin, const vec3 &xaxis, const vec3 &yaxis)
position operator* (position const &p, transf const &tr)
vec3 operator* (vec3 const &v, transf const &tr)
transf operator* (transf const &tr1, transf const &tr2)
std::ostream & operator<< (std::ostream &os, const transf &tr)
vec3 operator> (vec3 const &v, transf const &tr)
std::istream & operator>> (std::istream &is, transf &tr)
transf rotate_transf (double angle, const vec3 &axis)
transf rotXYZ (double, double, double)
transf translate_transf (const vec3 &v)

Detailed Description

A rigid body transformation.

The transform is stored as a rotation quaternion and a translation vector. A rotation matrix version is also stored so that it does not need to be recomputed each time it is requested. (This maybe eliminated at some point).

Definition at line 422 of file matvec3D.h.


Constructor & Destructor Documentation

transf::transf (  )  [inline]

Default constructor, initializes the transform to the identity

Definition at line 436 of file matvec3D.h.

transf::transf ( const Quaternion r,
const vec3 d 
) [inline]

Initializes transform with a rotation quaternion and translation vector

Definition at line 439 of file matvec3D.h.

transf::transf ( const mat3 r,
const vec3 d 
) [inline]

Initializes transform with a rotation matrix and translation vector

Definition at line 442 of file matvec3D.h.

transf::transf ( const SoTransform *  IVt  )  [inline]

Initializes transform using an Inventor transform.

Definition at line 445 of file matvec3D.h.


Member Function Documentation

const mat3& transf::affine (  )  const [inline]

Returns the rotation portion of the transform as a 3x3 matrix.

Definition at line 463 of file matvec3D.h.

transf transf::inverse (  )  const [inline]

Returns the inverse transformation.

Definition at line 1221 of file matvec3D.h.

void transf::jacobian ( double  jac[]  ) 

Creates a 6x6 jacobian from this transform.

Creates a 6x6 jacobian from a transform. Code adapted from Peter Corke's Robot Toolbox for MATLAB.

MATLAB representation:

	J = [	t(1:3,1)'	cross(t(1:3,4),t(1:3,1))'
			t(1:3,2)'	cross(t(1:3,4),t(1:3,2))'
			t(1:3,3)'	cross(t(1:3,4),t(1:3,3))'
			zeros(3,3)		t(1:3,1:3)'		];

The jacobian is returned is in column-major format.

Definition at line 185 of file matvec.cpp.

bool transf::operator!= ( transf const &  tr  )  const [inline]

Returns the negation of the == operator.

Definition at line 481 of file matvec3D.h.

transf const & transf::operator= ( transf const &  tr  )  [inline]

Assignment operator, copies transform tr.

Definition at line 1228 of file matvec3D.h.

bool transf::operator== ( transf const &  tr  )  const [inline]

Compares two transforms. Returns true if both the rotations and translations are equal (according to their comparators).

Definition at line 1354 of file matvec3D.h.

const Quaternion& transf::rotation (  )  const [inline]

Returns the rotation portion of the transform.

Definition at line 460 of file matvec3D.h.

void transf::set ( const SoTransform *  IVt  )  [inline]

Sets the value of this transform by converting an Inventor transform.

Definition at line 1303 of file matvec3D.h.

void transf::set ( const mat3 r,
const vec3 d 
) [inline]

Sets value of the transform with the rotation r and the translation d

Definition at line 455 of file matvec3D.h.

void transf::set ( const Quaternion r,
const vec3 d 
) [inline]

Sets value of the transform with the rotation r and the translation d

Definition at line 449 of file matvec3D.h.

void transf::tocol_Mat4 ( col_Mat4  colTran  )  const [inline]

Converts this transform to the collision system format, a 4x4 matrix.

Definition at line 1288 of file matvec3D.h.

void transf::toColMajorMatrix ( double  mat[][4]  )  const [inline]

Converts this transform to a column major 4x4 matrix

Definition at line 1256 of file matvec3D.h.

void transf::toRowMajorMatrix ( double  mat[][4]  )  const [inline]

Converts this transform to a row major 4x4 matrix

Definition at line 1272 of file matvec3D.h.

void transf::toSoTransform ( SoTransform *  IVt  )  const [inline]

Converts this transform to Inventor format.

Definition at line 1249 of file matvec3D.h.

const vec3& transf::translation (  )  const [inline]

Returns the translation portion of the transform.

Definition at line 466 of file matvec3D.h.


Friends And Related Function Documentation

transf coordinate_transf ( const position origin,
const vec3 xaxis,
const vec3 yaxis 
) [friend]

Helper function that creates a tranform from the global frame to the new frame with its origin at position o, and with the given x and y axes.

Definition at line 1386 of file matvec3D.h.

position operator* ( position const &  p,
transf const &  tr 
) [friend]

Returns the result of transforming position p with transform tr.

Definition at line 1344 of file matvec3D.h.

vec3 operator* ( vec3 const &  v,
transf const &  tr 
) [friend]

Returns a vector that is the result of rotating vector v using transform tr.

Definition at line 1328 of file matvec3D.h.

transf operator* ( transf const &  tr1,
transf const &  tr2 
) [friend]

Multiplies two transforms.

Definition at line 1317 of file matvec3D.h.

std::ostream& operator<< ( std::ostream &  os,
const transf tr 
) [friend]

Writes the 7 values of a transform tr formated as "(w, x, y, z) [v1,v2,v3]" to stream os.

Definition at line 578 of file matvec.cpp.

vec3 operator> ( vec3 const &  v,
transf const &  tr 
) [friend]

Definition at line 1334 of file matvec3D.h.

std::istream& operator>> ( std::istream &  is,
transf tr 
) [friend]

Reads the 7 values of a transform tr formated as "(w, x, y, z) [v1,v2,v3]" from stream is.

Definition at line 560 of file matvec.cpp.

transf rotate_transf ( double  angle,
const vec3 axis 
) [friend]

Helper function that creates a tranform that has a rotation of angle radians about axis, and a zero translation.

Definition at line 1376 of file matvec3D.h.

transf rotXYZ ( double  rx,
double  ry,
double  rz 
) [friend]

Definition at line 1395 of file matvec3D.h.

transf translate_transf ( const vec3 v  )  [friend]

Helper function that creates a transform with an identity rotation and a translation equal to vector v.

Definition at line 1366 of file matvec3D.h.


Member Data Documentation

const transf transf::IDENTITY [static]

The Identity transform (1,0,0,0)[0,0,0].

Definition at line 502 of file matvec3D.h.

mat3 transf::R [private]

A 3x3 matrix storing the current rotation.

Definition at line 425 of file matvec3D.h.

A 4x1 Quaternion storing the current rotation.

Definition at line 431 of file matvec3D.h.

vec3 transf::t [private]

A 3x1 vector storing the current translation.

Definition at line 428 of file matvec3D.h.


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


graspit
Author(s):
autogenerated on Wed Jan 25 11:00:26 2012