Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044 #ifndef VERTEX_POSE_H_
00045 #define VERTEX_POSE_H_
00046
00047 #include <g2o/config.h>
00048 #include <g2o/core/base_vertex.h>
00049 #include <g2o/core/hyper_graph_action.h>
00050 #include <g2o/stuff/misc.h>
00051
00052 #include <teb_local_planner/pose_se2.h>
00053
00054 namespace teb_local_planner
00055 {
00056
00063 class VertexPose : public g2o::BaseVertex<3, PoseSE2 >
00064 {
00065 public:
00066
00071 VertexPose(bool fixed = false)
00072 {
00073 setToOriginImpl();
00074 setFixed(fixed);
00075 }
00076
00082 VertexPose(const PoseSE2& pose, bool fixed = false)
00083 {
00084 _estimate = pose;
00085 setFixed(fixed);
00086 }
00087
00094 VertexPose(const Eigen::Ref<const Eigen::Vector2d>& position, double theta, bool fixed = false)
00095 {
00096 _estimate.position() = position;
00097 _estimate.theta() = theta;
00098 setFixed(fixed);
00099 }
00100
00108 VertexPose(double x, double y, double theta, bool fixed = false)
00109 {
00110 _estimate.x() = x;
00111 _estimate.y() = y;
00112 _estimate.theta() = theta;
00113 setFixed(fixed);
00114 }
00115
00119 ~VertexPose() {}
00120
00126 PoseSE2& pose() {return _estimate;}
00127
00133 const PoseSE2& pose() const {return _estimate;}
00134
00135
00141 Eigen::Vector2d& position() {return _estimate.position();}
00142
00148 const Eigen::Vector2d& position() const {return _estimate.position();}
00149
00154 double& x() {return _estimate.x();}
00155
00160 const double& x() const {return _estimate.x();}
00161
00166 double& y() {return _estimate.y();}
00167
00172 const double& y() const {return _estimate.y();}
00173
00178 double& theta() {return _estimate.theta();}
00179
00184 const double& theta() const {return _estimate.theta();}
00185
00189 virtual void setToOriginImpl()
00190 {
00191 _estimate.setZero();
00192 }
00193
00200 virtual void oplusImpl(const double* update)
00201 {
00202 _estimate.plus(update);
00203 }
00204
00211 virtual bool read(std::istream& is)
00212 {
00213 is >> _estimate.x() >> _estimate.y() >> _estimate.theta();
00214 return true;
00215 }
00216
00223 virtual bool write(std::ostream& os) const
00224 {
00225 os << _estimate.x() << " " << _estimate.y() << _estimate.theta();
00226 return os.good();
00227 }
00228
00229 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00230 };
00231
00232 }
00233
00234 #endif // VERTEX_POSE_H_