Class to describe a transformation of poses in 2D. This inplies a translation in x and y direction each and a rotation. More...
#include <Transformation2D.h>
Class to describe a transformation of poses in 2D. This inplies a translation in x and y direction each and a rotation.
Definition at line 28 of file Transformation2D.h.
Transformation2D::Transformation2D | ( | double | x, |
double | y, | ||
double | theta | ||
) |
Constructor that initializes the members.
x | translation in x direction in m |
y | translation in y direction in m |
theta | rotation in radiants |
Transformation2D::Transformation2D | ( | const CVec2 & | vec, |
double | theta | ||
) |
Constructor that initializes the members.
vec | a vector which represents the translation in x and y direction |
theta | rotation in radiants |
Default constructor sets all members to 0.0.
Default destructor.
Transformation2D Transformation2D::abs | ( | ) | const |
Applies abs() on every attribute.
Transformation2D Transformation2D::inverse | ( | ) | const |
Inverts the transformation, scales every attribute with -1.
bool Transformation2D::operator!= | ( | Transformation2D | t | ) | const |
Transformation2D Transformation2D::operator* | ( | float | factor | ) | const |
Scales a transformation by a factor
Transformation2D& Transformation2D::operator*= | ( | float | factor | ) |
Transformation2D Transformation2D::operator+ | ( | Transformation2D | t | ) | const |
Adds two transformations.
Transformation2D& Transformation2D::operator+= | ( | Transformation2D | t | ) |
Transformation2D Transformation2D::operator- | ( | Transformation2D | t | ) | const |
Subtracts two transformations.
Transformation2D& Transformation2D::operator-= | ( | Transformation2D | t | ) |
Transformation2D Transformation2D::operator/ | ( | float | factor | ) | const |
Scales a transformation by a factor
Transformation2D& Transformation2D::operator/= | ( | float | factor | ) |
bool Transformation2D::operator< | ( | Transformation2D | t | ) | const |
bool Transformation2D::operator<= | ( | Transformation2D | t | ) | const |
Compare transformations. (attention: algebraic signs are taken into account, if necessary use fabs())
bool Transformation2D::operator== | ( | Transformation2D | t | ) | const |
Test equality of transformations.
bool Transformation2D::operator> | ( | Transformation2D | t | ) | const |
bool Transformation2D::operator>= | ( | Transformation2D | t | ) | const |
void Transformation2D::set | ( | double | x, |
double | y, | ||
double | theta | ||
) |
Sets the values of transformation.
x | translation in x direction in mm |
y | translation in y direction in mm |
theta | rotation in radiants |
double Transformation2D::theta | ( | ) | const |
Returns the rotation in radiants.
std::string Transformation2D::toString | ( | ) | const |
Returns the string representation of the transformation.
Reimplemented from CVec2.
Point2D Transformation2D::transform | ( | const Point2D & | point | ) | const |
Transformes points by first rotation, then translating.
std::vector<Point2D> Transformation2D::transform | ( | const std::vector< Point2D > & | points | ) | const |
Line2D Transformation2D::transform | ( | const Line2D & | line | ) | const |
Transformes lines by first rotation, then translating.
std::vector<Line2D> Transformation2D::transform | ( | const std::vector< Line2D > & | lines | ) | const |
double Transformation2D::m_Theta [private] |
Definition at line 140 of file Transformation2D.h.