#include <rtcTransform2D.h>

Public Member Functions | |
| void | apply (Vec2< T > &v) const |
| Vec2< T > | apply (const Vec2< T > &v) const |
| void | get (Rotation2D< T > &rot, Vec2< T > &trans) const |
| void | get (T &theta, T &dx, T &dy) const |
| Rotation2D< T > | getRot () const |
| void | getRot (T &dtheta) const |
| Vec2< T > | getTrans () const |
| void | getTrans (T &dx, T &dy) const |
| Transform2D< T > | inverted () const |
| Vec< T, 3 > | operator* (const Vec2< T > &v) const |
| Transform2D< T > | relativeTo (const Transform2D< T > &referenceFrame) const |
| void | rotate (T theta) |
| void | set (const Rotation2D< T > &rot) |
| void | set (const Vec2< T > &trans) |
| void | set (const Rotation2D< T > &rot, const Vec2< T > &trans) |
| void | set (const T &dtheta, const T &dx, const T &dy) |
| Transform2D () | |
| Transform2D (const Mat< T, 3, 3 > &m) | |
| Transform2D (const SMat3< T > &m) | |
| Transform2D (const Rotation2D< T > &rot) | |
| Transform2D (const Vec2< T > &trans) | |
| Transform2D (const Rotation2D< T > &rot, const Vec2< T > &trans) | |
| Transform2D (const T &dtheta, const T &dx, const T &dy) | |
| void | translate (T x, T y) |
| void | translate (const Vec2< T > &t) |
The Tranform2D Matrix Class
Defines transformation class for rigid body rotations and translations that knows how to construct itself from rotation matrices.
Definition at line 47 of file rtcTransform2D.h.
| rtc::Transform2D< T >::Transform2D | ( | ) | [inline] |
Ctor that initializes to no rotation and no translation.
Definition at line 103 of file rtcTransform2D.h.
| rtc::Transform2D< T >::Transform2D | ( | const Mat< T, 3, 3 > & | m | ) | [inline] |
Ctor that initializes from Mat<T,3,3>.
Definition at line 143 of file rtcTransform2D.h.
| rtc::Transform2D< T >::Transform2D | ( | const SMat3< T > & | m | ) | [inline] |
Ctor that initializes from SMat<T,3>.
Definition at line 131 of file rtcTransform2D.h.
| rtc::Transform2D< T >::Transform2D | ( | const Rotation2D< T > & | r | ) | [inline] |
Ctor that initializes to the given rotation and no translation.
Definition at line 110 of file rtcTransform2D.h.
| rtc::Transform2D< T >::Transform2D | ( | const Vec2< T > & | t | ) | [inline] |
Ctor that initializes to no rotation and the given translation.
Definition at line 117 of file rtcTransform2D.h.
| rtc::Transform2D< T >::Transform2D | ( | const Rotation2D< T > & | rot, |
| const Vec2< T > & | trans | ||
| ) | [inline] |
Ctor that starts with the given rotation and translation.
Definition at line 124 of file rtcTransform2D.h.
| rtc::Transform2D< T >::Transform2D | ( | const T & | dtheta, |
| const T & | dx, | ||
| const T & | dy | ||
| ) | [inline] |
Ctor that initializes from dx, dy, dtheta.
Definition at line 136 of file rtcTransform2D.h.
| void rtc::Transform2D< T >::apply | ( | Vec2< T > & | v | ) | const [inline] |
Helper function that allows a transform to operate on a point.
Definition at line 277 of file rtcTransform2D.h.
| Vec2< T > rtc::Transform2D< T >::apply | ( | const Vec2< T > & | v | ) | const [inline] |
Helper function that allows a transform to operate on a point.
Definition at line 285 of file rtcTransform2D.h.
| void rtc::Transform2D< T >::get | ( | Rotation2D< T > & | r, |
| Vec2< T > & | t | ||
| ) | const [inline] |
Get the rotation and translation
Definition at line 150 of file rtcTransform2D.h.
| void rtc::Transform2D< T >::get | ( | T & | theta, |
| T & | dx, | ||
| T & | dy | ||
| ) | const [inline] |
Get the rotation and translation
Definition at line 160 of file rtcTransform2D.h.
| Rotation2D< T > rtc::Transform2D< T >::getRot | ( | ) | const [inline] |
Get the rotation
Definition at line 186 of file rtcTransform2D.h.
| void rtc::Transform2D< T >::getRot | ( | T & | dtheta | ) | const [inline] |
Get the rotation
Definition at line 195 of file rtcTransform2D.h.
| Vec2< T > rtc::Transform2D< T >::getTrans | ( | ) | const [inline] |
Get the translation
Definition at line 169 of file rtcTransform2D.h.
| void rtc::Transform2D< T >::getTrans | ( | T & | dx, |
| T & | dy | ||
| ) | const [inline] |
Get the translation
Definition at line 177 of file rtcTransform2D.h.
| Transform2D< T > rtc::Transform2D< T >::inverted | ( | ) | const [inline] |
Fast inverse of a rigid transform matrix. M = [ r t] [ 0 1]
inv(M) = [ r' -r'*t] [ 0 1]
Reimplemented from rtc::SMat3< T >.
Definition at line 298 of file rtcTransform2D.h.
| Vec< T, 3 > rtc::Transform2D< T >::operator* | ( | const Vec2< T > & | v | ) | const [inline] |
Helper function that allows a tranform to operate on a point.
Definition at line 270 of file rtcTransform2D.h.
| Transform2D< T > rtc::Transform2D< T >::relativeTo | ( | const Transform2D< T > & | referenceFrame | ) | const [inline] |
Converts to a new coordinate frame
Definition at line 309 of file rtcTransform2D.h.
| void rtc::Transform2D< T >::rotate | ( | T | theta | ) | [inline] |
Apply a rotation to the transform
Definition at line 239 of file rtcTransform2D.h.
| void rtc::Transform2D< T >::set | ( | const Rotation2D< T > & | r | ) | [inline] |
Set only the rotation portion of the Transform2D.
Definition at line 205 of file rtcTransform2D.h.
| void rtc::Transform2D< T >::set | ( | const Vec2< T > & | t | ) | [inline] |
Set only the translation portion of the Transform2D.
Definition at line 215 of file rtcTransform2D.h.
| void rtc::Transform2D< T >::set | ( | const Rotation2D< T > & | r, |
| const Vec2< T > & | t | ||
| ) | [inline] |
Set to the given rotation and translation
Definition at line 224 of file rtcTransform2D.h.
| void rtc::Transform2D< T >::set | ( | const T & | dtheta, |
| const T & | dx, | ||
| const T & | dy | ||
| ) | [inline] |
Set to the given rotation dtheta and translation dx/dy
Definition at line 232 of file rtcTransform2D.h.
| void rtc::Transform2D< T >::translate | ( | T | _x, |
| T | _y | ||
| ) | [inline] |
Apply a translation to the transform
Definition at line 253 of file rtcTransform2D.h.
| void rtc::Transform2D< T >::translate | ( | const Vec2< T > & | t | ) | [inline] |
Apply a translation to the transform
Definition at line 262 of file rtcTransform2D.h.