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>
Public Member Functions | |
| virtual void | oplusImpl (const double *update) |
Define the update increment . A simple addition for the position. The angle is first added to the previous estimated angle and afterwards normalized to the interval . | |
| PoseSE2 & | pose () |
| Access the pose. | |
| const PoseSE2 & | pose () const |
| Access the pose (read-only) | |
| Eigen::Vector2d & | position () |
| Access the 2D position part. | |
| const Eigen::Vector2d & | position () const |
| Access the 2D position part (read-only) | |
| virtual bool | read (std::istream &is) |
| Read an estimate from an input stream. First the x-coordinate followed by y and the yaw angle. | |
| virtual void | setToOriginImpl () |
| Set the underlying estimate (2D vector) to zero. | |
| double & | theta () |
| Access the orientation part (yaw angle) of the pose. | |
| const double & | theta () const |
| Access the orientation part (yaw angle) of the pose (read-only) | |
| VertexPose (bool fixed=false) | |
| Default constructor. | |
| VertexPose (const PoseSE2 &pose, bool fixed=false) | |
| Construct pose using a given PoseSE2. | |
| VertexPose (const Eigen::Ref< const Eigen::Vector2d > &position, double theta, bool fixed=false) | |
| Construct pose using a given 2D position vector and orientation. | |
| VertexPose (double x, double y, double theta, bool fixed=false) | |
| Construct pose using single components x, y, and the yaw angle. | |
| virtual bool | write (std::ostream &os) const |
| Write the estimate to an output stream First the x-coordinate followed by y and the yaw angle. | |
| double & | x () |
| Access the x-coordinate the pose. | |
| const double & | x () const |
| Access the x-coordinate the pose (read-only) | |
| double & | y () |
| Access the y-coordinate the pose. | |
| const double & | y () const |
| Access the y-coordinate the pose (read-only) | |
| ~VertexPose () | |
| Destructs the VertexPose. | |
This class stores and wraps a SE2 pose (position and orientation) into a vertex that can be optimized via g2o.
Definition at line 63 of file vertex_pose.h.
| teb_local_planner::VertexPose::VertexPose | ( | bool | fixed = false | ) | [inline] |
Default constructor.
| fixed | if true, this vertex is considered fixed during optimization [default: false] |
Definition at line 71 of file vertex_pose.h.
| teb_local_planner::VertexPose::VertexPose | ( | const PoseSE2 & | pose, |
| bool | fixed = false |
||
| ) | [inline] |
Construct pose using a given PoseSE2.
| pose | PoseSE2 defining the pose [x, y, angle_rad] |
| fixed | if true, this vertex is considered fixed during optimization [default: false] |
Definition at line 82 of file vertex_pose.h.
| 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.
| position | Eigen::Vector2d containing x and y coordinates |
| theta | yaw-angle |
| fixed | if true, this vertex is considered fixed during optimization [default: false] |
Definition at line 94 of file vertex_pose.h.
| 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.
| x | x-coordinate |
| y | y-coordinate |
| theta | yaw angle in rad |
| fixed | if true, this vertex is considered fixed during optimization [default: false] |
Definition at line 108 of file vertex_pose.h.
| teb_local_planner::VertexPose::~VertexPose | ( | ) | [inline] |
Destructs the VertexPose.
Definition at line 119 of file vertex_pose.h.
| virtual void teb_local_planner::VertexPose::oplusImpl | ( | const double * | update | ) | [inline, virtual] |
Define the update increment
. A simple addition for the position. The angle is first added to the previous estimated angle and afterwards normalized to the interval
.
| update | increment that should be added to the previous esimate |
Definition at line 200 of file vertex_pose.h.
| PoseSE2& teb_local_planner::VertexPose::pose | ( | ) | [inline] |
Access the pose.
Definition at line 126 of file vertex_pose.h.
| const PoseSE2& teb_local_planner::VertexPose::pose | ( | ) | const [inline] |
Access the pose (read-only)
Definition at line 133 of file vertex_pose.h.
| Eigen::Vector2d& teb_local_planner::VertexPose::position | ( | ) | [inline] |
Access the 2D position part.
Definition at line 141 of file vertex_pose.h.
| const Eigen::Vector2d& teb_local_planner::VertexPose::position | ( | ) | const [inline] |
Access the 2D position part (read-only)
Definition at line 148 of file vertex_pose.h.
| virtual bool teb_local_planner::VertexPose::read | ( | std::istream & | is | ) | [inline, virtual] |
Read an estimate from an input stream. First the x-coordinate followed by y and the yaw angle.
| is | input stream |
true Definition at line 211 of file vertex_pose.h.
| virtual void teb_local_planner::VertexPose::setToOriginImpl | ( | ) | [inline, virtual] |
Set the underlying estimate (2D vector) to zero.
Definition at line 189 of file vertex_pose.h.
| double& teb_local_planner::VertexPose::theta | ( | ) | [inline] |
Access the orientation part (yaw angle) of the pose.
Definition at line 178 of file vertex_pose.h.
| const double& teb_local_planner::VertexPose::theta | ( | ) | const [inline] |
Access the orientation part (yaw angle) of the pose (read-only)
Definition at line 184 of file vertex_pose.h.
| virtual bool teb_local_planner::VertexPose::write | ( | std::ostream & | os | ) | const [inline, virtual] |
Write the estimate to an output stream First the x-coordinate followed by y and the yaw angle.
| os | output stream |
true if the export was successful, otherwise false Definition at line 223 of file vertex_pose.h.
| double& teb_local_planner::VertexPose::x | ( | ) | [inline] |
Access the x-coordinate the pose.
Definition at line 154 of file vertex_pose.h.
| const double& teb_local_planner::VertexPose::x | ( | ) | const [inline] |
Access the x-coordinate the pose (read-only)
Definition at line 160 of file vertex_pose.h.
| double& teb_local_planner::VertexPose::y | ( | ) | [inline] |
Access the y-coordinate the pose.
Definition at line 166 of file vertex_pose.h.
| const double& teb_local_planner::VertexPose::y | ( | ) | const [inline] |
Access the y-coordinate the pose (read-only)
Definition at line 172 of file vertex_pose.h.