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 #ifndef POSE_SE2_H_
00040 #define POSE_SE2_H_
00041
00042 #include <g2o/stuff/misc.h>
00043
00044 #include <Eigen/Core>
00045 #include <teb_local_planner/misc.h>
00046 #include <geometry_msgs/Pose.h>
00047 #include <tf/transform_datatypes.h>
00048
00049 namespace teb_local_planner
00050 {
00051
00057 class PoseSE2
00058 {
00059 public:
00060
00062
00063
00067 PoseSE2()
00068 {
00069 setZero();
00070 }
00071
00077 PoseSE2(const Eigen::Ref<const Eigen::Vector2d>& position, double theta)
00078 {
00079 _position = position;
00080 _theta = theta;
00081 }
00082
00089 PoseSE2(double x, double y, double theta)
00090 {
00091 _position.coeffRef(0) = x;
00092 _position.coeffRef(1) = y;
00093 _theta = theta;
00094 }
00095
00100 PoseSE2(const geometry_msgs::Pose& pose)
00101 {
00102 _position.coeffRef(0) = pose.position.x;
00103 _position.coeffRef(1) = pose.position.y;
00104 _theta = tf::getYaw( pose.orientation );
00105 }
00106
00111 PoseSE2(const tf::Pose& pose)
00112 {
00113 _position.coeffRef(0) = pose.getOrigin().getX();
00114 _position.coeffRef(1) = pose.getOrigin().getY();
00115 _theta = tf::getYaw( pose.getRotation() );
00116 }
00117
00122 PoseSE2(const PoseSE2& pose)
00123 {
00124 _position = pose._position;
00125 _theta = pose._theta;
00126 }
00127
00129
00130
00134 ~PoseSE2() {}
00135
00136
00138
00139
00145 Eigen::Vector2d& position() {return _position;}
00146
00152 const Eigen::Vector2d& position() const {return _position;}
00153
00158 double& x() {return _position.coeffRef(0);}
00159
00164 const double& x() const {return _position.coeffRef(0);}
00165
00170 double& y() {return _position.coeffRef(1);}
00171
00176 const double& y() const {return _position.coeffRef(1);}
00177
00182 double& theta() {return _theta;}
00183
00188 const double& theta() const {return _theta;}
00189
00193 void setZero()
00194 {
00195 _position.setZero();
00196 _theta = 0;
00197 }
00198
00203 void toPoseMsg(geometry_msgs::Pose& pose) const
00204 {
00205 pose.position.x = _position.x();
00206 pose.position.y = _position.y();
00207 pose.position.z = 0;
00208 pose.orientation = tf::createQuaternionMsgFromYaw(_theta);
00209 }
00210
00215 Eigen::Vector2d orientationUnitVec() const {return Eigen::Vector2d(std::cos(_theta), std::sin(_theta));}
00216
00218
00219
00221
00222
00227 void scale(double factor)
00228 {
00229 _position *= factor;
00230 _theta = g2o::normalize_theta( _theta*factor );
00231 }
00232
00238 void plus(const double* pose_as_array)
00239 {
00240 _position.coeffRef(0) += pose_as_array[0];
00241 _position.coeffRef(1) += pose_as_array[1];
00242 _theta = g2o::normalize_theta( _theta + pose_as_array[2] );
00243 }
00244
00252 void averageInPlace(const PoseSE2& pose1, const PoseSE2& pose2)
00253 {
00254 _position = (pose1._position + pose2._position)/2;
00255 _theta = g2o::average_angle(pose1._theta, pose2._theta);
00256 }
00257
00266 static PoseSE2 average(const PoseSE2& pose1, const PoseSE2& pose2)
00267 {
00268 return PoseSE2( (pose1._position + pose2._position)/2 , g2o::average_angle(pose1._theta, pose2._theta) );
00269 }
00270
00272
00273
00275
00276
00282 PoseSE2& operator=( const PoseSE2& rhs )
00283 {
00284 if (&rhs != this)
00285 {
00286 _position = rhs._position;
00287 _theta = rhs._theta;
00288 }
00289 return *this;
00290 }
00291
00296 PoseSE2& operator+=(const PoseSE2& rhs)
00297 {
00298 _position += rhs._position;
00299 _theta = g2o::normalize_theta(_theta + rhs._theta);
00300 return *this;
00301 }
00302
00308 friend PoseSE2 operator+(PoseSE2 lhs, const PoseSE2& rhs)
00309 {
00310 return lhs += rhs;
00311 }
00312
00317 PoseSE2& operator-=(const PoseSE2& rhs)
00318 {
00319 _position -= rhs._position;
00320 _theta = g2o::normalize_theta(_theta - rhs._theta);
00321 return *this;
00322 }
00323
00329 friend PoseSE2 operator-(PoseSE2 lhs, const PoseSE2& rhs)
00330 {
00331 return lhs -= rhs;
00332 }
00333
00341 friend PoseSE2 operator*(PoseSE2 pose, double scalar)
00342 {
00343 pose._position *= scalar;
00344 pose._theta *= scalar;
00345 return pose;
00346 }
00347
00355 friend PoseSE2 operator*(double scalar, PoseSE2 pose)
00356 {
00357 pose._position *= scalar;
00358 pose._theta *= scalar;
00359 return pose;
00360 }
00361
00367 friend std::ostream& operator<< (std::ostream& stream, const PoseSE2& pose)
00368 {
00369 stream << "x: " << pose._position[0] << " y: " << pose._position[1] << " theta: " << pose._theta;
00370 return stream;
00371 }
00372
00374
00375
00376 private:
00377
00378 Eigen::Vector2d _position;
00379 double _theta;
00380
00381 public:
00382 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00383 };
00384
00385
00386 }
00387
00388 #endif // POSE_SE2_H_