Go to the documentation of this file.
42 #include <g2o/stuff/misc.h>
46 #include <geometry_msgs/Pose.h>
100 PoseSE2(
const geometry_msgs::Pose& pose)
164 const double&
x()
const {
return _position.coeffRef(0);}
176 const double&
y()
const {
return _position.coeffRef(1);}
203 void toPoseMsg(geometry_msgs::Pose& pose)
const
227 void scale(
double factor)
238 void plus(
const double* pose_as_array)
240 _position.coeffRef(0) += pose_as_array[0];
241 _position.coeffRef(1) += pose_as_array[1];
242 _theta = g2o::normalize_theta(
_theta + pose_as_array[2] );
254 _position = (pose1._position + pose2._position)/2;
255 _theta = g2o::average_angle(pose1._theta, pose2._theta);
268 return PoseSE2( (pose1._position + pose2._position)/2 , g2o::average_angle(pose1._theta, pose2._theta) );
361 pose._position *= scalar;
362 pose._theta *= scalar;
375 pose._position *= scalar;
376 pose._theta *= scalar;
387 stream <<
"x: " << pose._position[0] <<
" y: " << pose._position[1] <<
" theta: " << pose._theta;
400 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
406 #endif // POSE_SE2_H_
friend PoseSE2 operator-(PoseSE2 lhs, const PoseSE2 &rhs)
Arithmetic operator overload for subtractions.
double & x()
Access the x-coordinate the pose.
void toPoseMsg(geometry_msgs::Pose &pose) const
Convert PoseSE2 to a geometry_msgs::Pose.
double & y()
Access the y-coordinate the pose.
void rotateGlobal(double angle, bool adjust_theta=true)
Rotate pose globally.
void averageInPlace(const PoseSE2 &pose1, const PoseSE2 &pose2)
Get the mean / average of two poses and store it in the caller class For the position part: 0....
Eigen::Vector2d _position
friend std::ostream & operator<<(std::ostream &stream, const PoseSE2 &pose)
Output stream operator.
PoseSE2 & operator=(const PoseSE2 &rhs)
Asignment operator.
static double getYaw(const geometry_msgs::Quaternion &msg_q)
~PoseSE2()
Destructs the PoseSE2.
double & theta()
Access the orientation part (yaw angle) of the pose.
Eigen::Vector2d & position()
Access the 2D position part.
friend PoseSE2 operator+(PoseSE2 lhs, const PoseSE2 &rhs)
Arithmetic operator overload for additions.
friend PoseSE2 operator*(PoseSE2 pose, double scalar)
Multiply pose with scalar and return copy without normalizing theta This operator is useful for calcu...
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
Eigen::Vector2d orientationUnitVec() const
Return the unit vector of the current orientation.
PoseSE2()
Default constructor.
PoseSE2 & operator-=(const PoseSE2 &rhs)
Compound assignment operator (subtraction)
void plus(const double *pose_as_array)
Increment the pose by adding a double[3] array The angle is normalized afterwards.
void setZero()
Set pose to [0,0,0].
PoseSE2 & operator+=(const PoseSE2 &rhs)
Compound assignment operator (addition)
static PoseSE2 average(const PoseSE2 &pose1, const PoseSE2 &pose2)
Get the mean / average of two poses and return the result (static) For the position part: 0....
void scale(double factor)
Scale all SE2 components (x,y,theta) and normalize theta afterwards to [-pi, pi].
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15