Public Member Functions | List of all members
teb_local_planner::VertexPose Class Reference

This class stores and wraps a SE2 pose (position and orientation) into a vertex that can be optimized via g2o. More...

#include <vertex_pose.h>

Inheritance diagram for teb_local_planner::VertexPose:
Inheritance graph
[legend]

Public Member Functions

virtual void oplusImpl (const double *update) override
 Define the update increment $ \mathbf{x}_{k+1} = \mathbf{x}_k + \Delta \mathbf{x} $. A simple addition for the position. The angle is first added to the previous estimated angle and afterwards normalized to the interval $ [-\pi \pi] $. More...
 
PoseSE2pose ()
 Access the pose. More...
 
const PoseSE2pose () const
 Access the pose (read-only) More...
 
Eigen::Vector2d & position ()
 Access the 2D position part. More...
 
const Eigen::Vector2d & position () const
 Access the 2D position part (read-only) More...
 
virtual bool read (std::istream &is) override
 Read an estimate from an input stream. First the x-coordinate followed by y and the yaw angle. More...
 
virtual void setToOriginImpl () override
 Set the underlying estimate (2D vector) to zero. More...
 
double & theta ()
 Access the orientation part (yaw angle) of the pose. More...
 
const double & theta () const
 Access the orientation part (yaw angle) of the pose (read-only) More...
 
 VertexPose (bool fixed=false)
 Default constructor. More...
 
 VertexPose (const Eigen::Ref< const Eigen::Vector2d > &position, double theta, bool fixed=false)
 Construct pose using a given 2D position vector and orientation. More...
 
 VertexPose (const PoseSE2 &pose, bool fixed=false)
 Construct pose using a given PoseSE2. More...
 
 VertexPose (double x, double y, double theta, bool fixed=false)
 Construct pose using single components x, y, and the yaw angle. More...
 
virtual bool write (std::ostream &os) const override
 Write the estimate to an output stream First the x-coordinate followed by y and the yaw angle. More...
 
double & x ()
 Access the x-coordinate the pose. More...
 
const double & x () const
 Access the x-coordinate the pose (read-only) More...
 
double & y ()
 Access the y-coordinate the pose. More...
 
const double & y () const
 Access the y-coordinate the pose (read-only) More...
 

Detailed Description

This class stores and wraps a SE2 pose (position and orientation) into a vertex that can be optimized via g2o.

See also
PoseSE2
VertexTimeDiff

Definition at line 104 of file vertex_pose.h.

Constructor & Destructor Documentation

◆ VertexPose() [1/4]

teb_local_planner::VertexPose::VertexPose ( bool  fixed = false)
inline

Default constructor.

Parameters
fixedif true, this vertex is considered fixed during optimization [default: false]

Definition at line 112 of file vertex_pose.h.

◆ VertexPose() [2/4]

teb_local_planner::VertexPose::VertexPose ( const PoseSE2 pose,
bool  fixed = false 
)
inline

Construct pose using a given PoseSE2.

Parameters
posePoseSE2 defining the pose [x, y, angle_rad]
fixedif true, this vertex is considered fixed during optimization [default: false]

Definition at line 123 of file vertex_pose.h.

◆ VertexPose() [3/4]

teb_local_planner::VertexPose::VertexPose ( const Eigen::Ref< const Eigen::Vector2d > &  position,
double  theta,
bool  fixed = false 
)
inline

Construct pose using a given 2D position vector and orientation.

Parameters
positionEigen::Vector2d containing x and y coordinates
thetayaw-angle
fixedif true, this vertex is considered fixed during optimization [default: false]

Definition at line 135 of file vertex_pose.h.

◆ VertexPose() [4/4]

teb_local_planner::VertexPose::VertexPose ( double  x,
double  y,
double  theta,
bool  fixed = false 
)
inline

Construct pose using single components x, y, and the yaw angle.

Parameters
xx-coordinate
yy-coordinate
thetayaw angle in rad
fixedif true, this vertex is considered fixed during optimization [default: false]

Definition at line 149 of file vertex_pose.h.

Member Function Documentation

◆ oplusImpl()

virtual void teb_local_planner::VertexPose::oplusImpl ( const double *  update)
inlineoverridevirtual

Define the update increment $ \mathbf{x}_{k+1} = \mathbf{x}_k + \Delta \mathbf{x} $. A simple addition for the position. The angle is first added to the previous estimated angle and afterwards normalized to the interval $ [-\pi \pi] $.

Parameters
updateincrement that should be added to the previous esimate

Definition at line 236 of file vertex_pose.h.

◆ pose() [1/2]

PoseSE2& teb_local_planner::VertexPose::pose ( )
inline

Access the pose.

See also
estimate
Returns
reference to the PoseSE2 estimate

Definition at line 162 of file vertex_pose.h.

◆ pose() [2/2]

const PoseSE2& teb_local_planner::VertexPose::pose ( ) const
inline

Access the pose (read-only)

See also
estimate
Returns
const reference to the PoseSE2 estimate

Definition at line 169 of file vertex_pose.h.

◆ position() [1/2]

Eigen::Vector2d& teb_local_planner::VertexPose::position ( )
inline

Access the 2D position part.

See also
estimate
Returns
reference to the 2D position part

Definition at line 177 of file vertex_pose.h.

◆ position() [2/2]

const Eigen::Vector2d& teb_local_planner::VertexPose::position ( ) const
inline

Access the 2D position part (read-only)

See also
estimate
Returns
const reference to the 2D position part

Definition at line 184 of file vertex_pose.h.

◆ read()

virtual bool teb_local_planner::VertexPose::read ( std::istream &  is)
inlineoverridevirtual

Read an estimate from an input stream. First the x-coordinate followed by y and the yaw angle.

Parameters
isinput stream
Returns
always true

Definition at line 247 of file vertex_pose.h.

◆ setToOriginImpl()

virtual void teb_local_planner::VertexPose::setToOriginImpl ( )
inlineoverridevirtual

Set the underlying estimate (2D vector) to zero.

Definition at line 225 of file vertex_pose.h.

◆ theta() [1/2]

double& teb_local_planner::VertexPose::theta ( )
inline

Access the orientation part (yaw angle) of the pose.

Returns
reference to the yaw angle

Definition at line 214 of file vertex_pose.h.

◆ theta() [2/2]

const double& teb_local_planner::VertexPose::theta ( ) const
inline

Access the orientation part (yaw angle) of the pose (read-only)

Returns
const reference to the yaw angle

Definition at line 220 of file vertex_pose.h.

◆ write()

virtual bool teb_local_planner::VertexPose::write ( std::ostream &  os) const
inlineoverridevirtual

Write the estimate to an output stream First the x-coordinate followed by y and the yaw angle.

Parameters
osoutput stream
Returns
true if the export was successful, otherwise false

Definition at line 259 of file vertex_pose.h.

◆ x() [1/2]

double& teb_local_planner::VertexPose::x ( )
inline

Access the x-coordinate the pose.

Returns
reference to the x-coordinate

Definition at line 190 of file vertex_pose.h.

◆ x() [2/2]

const double& teb_local_planner::VertexPose::x ( ) const
inline

Access the x-coordinate the pose (read-only)

Returns
const reference to the x-coordinate

Definition at line 196 of file vertex_pose.h.

◆ y() [1/2]

double& teb_local_planner::VertexPose::y ( )
inline

Access the y-coordinate the pose.

Returns
reference to the y-coordinate

Definition at line 202 of file vertex_pose.h.

◆ y() [2/2]

const double& teb_local_planner::VertexPose::y ( ) const
inline

Access the y-coordinate the pose (read-only)

Returns
const reference to the y-coordinate

Definition at line 208 of file vertex_pose.h.


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


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:16