Class Pose2D

Class Documentation

class Pose2D

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

Public Functions

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)
Pose2D &set(double x, const double y, double phi)

set the pose

set the pose

Parameters:
  • x

  • y

  • phi – (orientation)

  • x

  • y

  • phi – (orientation_)

Returns:

this reference

Returns:

this reference

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

Pose2D &set(const Pose2D &p)

set the pose

Parameters:

p – pose

Returns:

this reference

const Point2D &position() const

position

location as vector

Returns:

translational

Returns:

translational

Point2D &position()

location as vector

Returns:

translational

const double &x() const

point in front of the pose

translational x component

Parameters:

d – distance ahead

Returns:

point

Returns:

x component

double &x()

translational y component

translational x component

Returns:

y component

Returns:

x component

const double &y() const

translational y component

Returns:

y component

double &y()

rotational component

translational y component

Returns:

rotation

Returns:

y component

const double &theta() const

rotational component

roational component

Returns:

rotation

Returns:

rotation

double &theta()

position

roational component

Returns:

rotation

Returns:

rotation

void set_x(double v)

set funktion for x

Parameters:

x – component

double get_x() const

get function for x

Returns:

x component

void set_y(double v)

set funktion for y

Parameters:

y – component

double get_y() const

get function for y

Returns:

y component

void set_theta(double v)

set funktion for theta

Parameters:

theta – component

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

transforms a point from pose target space into pose base space

transforms a point from pose target space into pose base space

Note

you have to update the cached cos and sin values in advance

Parameters:
  • src – point in pose target space

  • des – point in pose base space

  • src – point in pose target space

  • des – point in pose base space

Returns:

ref point in pose base space

Returns:

ref point in pose base space

Point2D transform_into_base(const Point2D &src) const

transforms a point from pose target space into pose base space

Note

you have to update the cached cos and sin values in advance

Parameters:

src – point in pose target space

Returns:

point in pose base space

Pose2D transform_into(const Pose2D &target) const

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

Parameters:

target – target frame

Returns:

pose in target frame

double get_theta() const

get function for theta

Returns:

theta component

void 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.

double theta_cos() const

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

Returns:

cos(theta)

double theta_sin() const

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

Returns:

sin(theta)

Point2D point_ahead(double d = 1.) const

computes a transformation matrix

point infront of the pose

Parameters:

d – distance ahead

Returns:

transformation

Returns:

point

void normalizeOrientation()

normalizes the orientation value betwenn -PI and PI

Tf2D tf() const

translational x component

computes a transformation matrix

Returns:

x component

Returns:

transformation

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

retuns a state vector [x, y, theta]

Returns:

state vector [x, y, theta]

Pose2D inv() const

invert pose

Returns:

inverted pose

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

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

adds a state vector [x, y, theta]

Parameters:
  • s – object

  • s – object

Returns:

pose

Returns:

this

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

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

substracts a state vector [x, y, theta]

Parameters:
  • s – object

  • s – object

Returns:

this

Returns:

this

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

returns x, y and theta as formated string

Parameters:

format – using printf format

Returns:

string

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

compares with within tolerance

Parameters:
  • o

  • tolerance

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

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

Parameters:

copy – t

Protected Functions

void update_cached_cos_sin() const

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

Protected Attributes

Point2D position_
double orientation_

position

mutable double costheta_

rotation in rad

double sintheta_
mutable bool cossin_uptodate_

Friends

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

Stream extraction

Parameters:
  • os – outputstream

  • o – object

Returns:

stream