Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
tuw::Pose2D Class Reference

#include <pose2d.h>

Public Member Functions

template<typename T >
void copyToROSPose (T &des) const
 
bool equal (const Pose2D &o, double tolerance) const
 
double get_theta () const
 
double get_x () const
 
double get_y () const
 
Pose2D inv () const
 
void normalizeOrientation ()
 
Pose2Doperator+= (const cv::Vec< double, 3 > &s)
 
Pose2Doperator-= (const cv::Vec< double, 3 > &s)
 
Point2D point_ahead (double d=1.) const
 
 Pose2D ()
 
 Pose2D (const Point2D &p, double orientation)
 
 Pose2D (const Pose2D &p)
 
 Pose2D (double x, double y, double orientation)
 
 Pose2D (const cv::Vec< double, 3 > &s)
 
const Point2Dposition () const
 
Point2Dposition ()
 
void recompute_cached_cos_sin () const
 
Pose2Dset (double x, const double y, double phi)
 
Pose2Dset (const Point2D &position, const Point2D &point_ahead)
 
Pose2Dset (const Pose2D &p)
 
void set_theta (double v)
 
void set_x (double v)
 
void set_y (double v)
 
cv::Vec< double, 3 > state_vector () const
 
std::string str (const char *format="[%6.4lf, %6.4lf, %6.5lf]") const
 
Tf2D tf () const
 
const double & theta () const
 
double & theta ()
 
double theta_cos () const
 
double theta_sin () const
 
Pose2D transform_into (const Pose2D &target) const
 
Point2Dtransform_into_base (const Point2D &src, Point2D &des) const
 
const double & x () const
 
double & x ()
 
const double & y () const
 
double & y ()
 

Protected Member Functions

void update_cached_cos_sin () const
 

Protected Attributes

bool cossin_uptodate_
 
double costheta_
 rotation in rad More...
 
double orientation_
 position More...
 
Point2D position_
 
double sintheta_
 

Friends

std::ostream & operator<< (std::ostream &os, const Pose2D &o)
 

Detailed Description

class to represent a pose in 2D space the class caches the cos(theta) and sin(theta) values

Definition at line 17 of file pose2d.h.

Constructor & Destructor Documentation

Pose2D::Pose2D ( )

Definition at line 4 of file pose2d.cpp.

Pose2D::Pose2D ( const Point2D p,
double  orientation 
)

Definition at line 5 of file pose2d.cpp.

Pose2D::Pose2D ( const Pose2D p)

Definition at line 6 of file pose2d.cpp.

Pose2D::Pose2D ( double  x,
double  y,
double  orientation 
)

Definition at line 7 of file pose2d.cpp.

Pose2D::Pose2D ( const cv::Vec< double, 3 > &  s)

Definition at line 8 of file pose2d.cpp.

Member Function Documentation

template<typename T >
void tuw::Pose2D::copyToROSPose ( T &  des) const
inline

Used to copy the Pose2D object into a ros geometry_msgs::Pose

Parameters
copyt

Definition at line 257 of file pose2d.h.

bool Pose2D::equal ( const Pose2D o,
double  tolerance 
) const

compares with within tolerance

Parameters
o
tolerance

Definition at line 271 of file pose2d.cpp.

double Pose2D::get_theta ( ) const

get function for theta

Returns
theta component

Definition at line 141 of file pose2d.cpp.

double Pose2D::get_x ( ) const

get function for x

Returns
x component

Definition at line 113 of file pose2d.cpp.

double Pose2D::get_y ( ) const

get function for y

Returns
y component

Definition at line 127 of file pose2d.cpp.

Pose2D Pose2D::inv ( ) const

invert pose

Returns
inverted pose

Definition at line 168 of file pose2d.cpp.

void Pose2D::normalizeOrientation ( )

normalizes the orientation value betwenn -PI and PI

Definition at line 147 of file pose2d.cpp.

Pose2D & Pose2D::operator+= ( const cv::Vec< double, 3 > &  s)

adds a state vector [x, y, theta] the orientation will be normalized between -PI and PI

Parameters
sobject
Returns
pose

adds a state vector [x, y, theta]

Parameters
sobject
Returns
this

Definition at line 191 of file pose2d.cpp.

Pose2D & Pose2D::operator-= ( const cv::Vec< double, 3 > &  s)

substracts a state vector [x, y, theta] the orientation will be normalized between -PI and PI

Parameters
sobject
Returns
this

substracts a state vector [x, y, theta]

Parameters
sobject
Returns
this

Definition at line 202 of file pose2d.cpp.

Point2D Pose2D::point_ahead ( double  d = 1.) const

computes a transformation matrix

Returns
transformation

point infront of the pose

Parameters
ddistance ahead
Returns
point

Definition at line 54 of file pose2d.cpp.

const Point2D & Pose2D::position ( ) const

position

Returns
translational

location as vector

Returns
translational

Definition at line 47 of file pose2d.cpp.

Point2D & Pose2D::position ( )

location as vector

Returns
translational

Definition at line 79 of file pose2d.cpp.

void Pose2D::recompute_cached_cos_sin ( ) const

enforces the recompuation of the cached value of cos(theta) and sin(theta), recomputing it only once when theta changes.

Definition at line 221 of file pose2d.cpp.

Pose2D & Pose2D::set ( double  x,
const double  y,
double  phi 
)

set the pose

Parameters
x
y
phi(orientation)
Returns
this reference

set the pose

Parameters
x
y
phi(orientation_)
Returns
this reference

Definition at line 16 of file pose2d.cpp.

Pose2D & Pose2D::set ( const Point2D position,
const Point2D point_ahead 
)

set the pose based on two points in world coordinates

Parameters
position
point_ahead
Returns
this reference

Definition at line 28 of file pose2d.cpp.

Pose2D & Pose2D::set ( const Pose2D p)

set the pose

Parameters
ppose
Returns
this reference

Definition at line 39 of file pose2d.cpp.

void Pose2D::set_theta ( double  v)

set funktion for theta

Parameters
thetacomponent

Definition at line 134 of file pose2d.cpp.

void Pose2D::set_x ( double  v)

set funktion for x

Parameters
xcomponent

Definition at line 106 of file pose2d.cpp.

void Pose2D::set_y ( double  v)

set funktion for y

Parameters
ycomponent

Definition at line 120 of file pose2d.cpp.

cv::Vec< double, 3 > Pose2D::state_vector ( ) const

retuns a state vector [x, y, theta]

Returns
state vector [x, y, theta]

Definition at line 161 of file pose2d.cpp.

std::string Pose2D::str ( const char *  format = "[%6.4lf, %6.4lf, %6.5lf]") const

returns x, y and theta as formated string

Parameters
formatusing printf format
Returns
string

Definition at line 259 of file pose2d.cpp.

Tf2D Pose2D::tf ( ) const

translational x component

Returns
x component

computes a transformation matrix

Returns
transformation

Definition at line 153 of file pose2d.cpp.

const double & Pose2D::theta ( ) const

rotational component

Returns
rotation

roational component

Returns
rotation

Definition at line 73 of file pose2d.cpp.

double & Pose2D::theta ( )

position

Returns
rotation

roational component

Returns
rotation

Definition at line 97 of file pose2d.cpp.

double Pose2D::theta_cos ( ) const

get a (cached) value of cos(theta), recomputing it only once when theta changes.

Returns
cos(theta)

Definition at line 241 of file pose2d.cpp.

double Pose2D::theta_sin ( ) const

get a (cached) value of cos(theta), recomputing it only once when theta changes.

Returns
sin(theta)

Definition at line 250 of file pose2d.cpp.

Pose2D Pose2D::transform_into ( const Pose2D target) const

transforms a pose into the target frame the orientation will be normalized between -PI and PI

Parameters
targettarget frame
Returns
pose in target frame

Definition at line 213 of file pose2d.cpp.

Point2D & Pose2D::transform_into_base ( const Point2D src,
Point2D des 
) const

transforms a point from pose target space into pose base space

Parameters
srcpoint in pose target space
despoint in pose base space
Returns
ref point in pose base space

Definition at line 178 of file pose2d.cpp.

void Pose2D::update_cached_cos_sin ( ) const
protected

Updates the cached value of cos(phi) and sin(phi), recomputing it only once when phi changes.

Definition at line 230 of file pose2d.cpp.

const double & Pose2D::x ( ) const

point in front of the pose

Parameters
ddistance ahead
Returns
point

translational x component

Returns
x component

Definition at line 61 of file pose2d.cpp.

double & Pose2D::x ( )

translational y component

Returns
y component

translational x component

Returns
x component

Definition at line 85 of file pose2d.cpp.

const double & Pose2D::y ( ) const

translational y component

Returns
y component

Definition at line 67 of file pose2d.cpp.

double & Pose2D::y ( )

rotational component

Returns
rotation

translational y component

Returns
y component

Definition at line 91 of file pose2d.cpp.

Friends And Related Function Documentation

std::ostream& operator<< ( std::ostream &  os,
const Pose2D o 
)
friend

Stream extraction

Parameters
osoutputstream
oobject
Returns
stream

Definition at line 231 of file pose2d.h.

Member Data Documentation

bool tuw::Pose2D::cossin_uptodate_
mutableprotected

Definition at line 23 of file pose2d.h.

double tuw::Pose2D::costheta_
mutableprotected

rotation in rad

Definition at line 22 of file pose2d.h.

double tuw::Pose2D::orientation_
protected

position

Definition at line 21 of file pose2d.h.

Point2D tuw::Pose2D::position_
protected

Definition at line 20 of file pose2d.h.

double tuw::Pose2D::sintheta_
mutableprotected

Definition at line 22 of file pose2d.h.


The documentation for this class was generated from the following files:


tuw_geometry
Author(s): Markus Bader
autogenerated on Mon Jun 10 2019 15:33:09