Public Member Functions | Static Public Member Functions | Static Public Attributes | Private Attributes | Friends
isam::Pose3d Class Reference

#include <Pose3d.h>

List of all members.

Public Member Functions

Pose3d exmap (const Vector6d &delta) const
Eigen::VectorXb is_angle () const
void of_point2d (const Point2d &p)
void of_point3d (const Point3d &p)
void of_pose2d (const Pose2d &p)
Pose3d ominus (const Pose3d &b) const
Pose3d oplus (const Pose3d &d) const
Eigen::Matrix4d oTw () const
double pitch () const
 Pose3d ()
 Pose3d (double x, double y, double z, double yaw, double pitch, double roll)
 Pose3d (const Eigen::MatrixXd &m)
 Pose3d (const Eigen::Isometry3d &T)
 Pose3d (const Point3d &t, const Rot3d &rot)
double roll () const
Rot3d rot () const
void set (double x, double y, double z, double yaw, double pitch, double roll)
void set (const Vector6d &v)
void set_pitch (double pitch)
void set_roll (double roll)
void set_x (double x)
void set_y (double y)
void set_yaw (double yaw)
void set_z (double z)
Point3d trans () const
Point3dh transform_from (const Point3dh &p) const
Point3d transform_from (const Point3d &p) const
Point3dh transform_to (const Point3dh &p) const
Point3d transform_to (const Point3d &p) const
Vector6d vector () const
void write (std::ostream &out) const
Eigen::Matrix4d wTo () const
double x () const
double y () const
double yaw () const
double z () const

Static Public Member Functions

static const char * name ()

Static Public Attributes

static
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
const int 
dim = 6

Private Attributes

Rot3d _rot
Point3d _t

Friends

std::ostream & operator<< (std::ostream &out, const Pose3d &p)

Detailed Description

Conventions:

Right-handed coordinate system (NED: north-east-down) X forward (along default motion of robot) Y right Z down

Rotations are represented using standard Euler angles yaw pitch roll

Note that Euler angles transform objects from the global into the local frame of the vehicle: First yaw rotates around Z (changing X and Y axes to X' and Y'), then pitch around the new Y' axis, and finally roll around the new X' axis.

In contrast, the returned rotation and transformation matrices are defined in the opposite direction: wTo transforms a point from the local (second) system to the global (first) system

Definition at line 69 of file Pose3d.h.


Constructor & Destructor Documentation

isam::Pose3d::Pose3d ( ) [inline]

Definition at line 85 of file Pose3d.h.

isam::Pose3d::Pose3d ( double  x,
double  y,
double  z,
double  yaw,
double  pitch,
double  roll 
) [inline]

Definition at line 87 of file Pose3d.h.

isam::Pose3d::Pose3d ( const Eigen::MatrixXd &  m) [inline]

Definition at line 89 of file Pose3d.h.

isam::Pose3d::Pose3d ( const Eigen::Isometry3d &  T) [inline, explicit]

Definition at line 105 of file Pose3d.h.

isam::Pose3d::Pose3d ( const Point3d t,
const Rot3d rot 
) [inline]

Definition at line 111 of file Pose3d.h.


Member Function Documentation

Pose3d isam::Pose3d::exmap ( const Vector6d delta) const [inline]

Definition at line 130 of file Pose3d.h.

Definition at line 173 of file Pose3d.h.

static const char* isam::Pose3d::name ( ) [inline, static]

Definition at line 81 of file Pose3d.h.

void isam::Pose3d::of_point2d ( const Point2d p) [inline]

Definition at line 160 of file Pose3d.h.

void isam::Pose3d::of_point3d ( const Point3d p) [inline]

Definition at line 164 of file Pose3d.h.

void isam::Pose3d::of_pose2d ( const Pose2d p) [inline]

Definition at line 156 of file Pose3d.h.

Pose3d isam::Pose3d::ominus ( const Pose3d b) const [inline]

Odometry d from b to this pose (a). Follows notation of Lu&Milios 1997. $ d = a \ominus b $

Parameters:
bBase frame.
Returns:
Global this (a) expressed in base frame b.

Definition at line 232 of file Pose3d.h.

Pose3d isam::Pose3d::oplus ( const Pose3d d) const [inline]

Calculate new pose b composed from this pose (a) and the odometry d. Follows notation of Lu&Milios 1997. $ b = a \oplus d $

Parameters:
dPose difference to add.
Returns:
d transformed from being local in this frame (a) to the global frame.

Definition at line 221 of file Pose3d.h.

Eigen::Matrix4d isam::Pose3d::oTw ( ) const [inline]

Convert Pose3 to homogeneous 4x4 transformation matrix. Avoids inverting wTo. The returned matrix is the world coordinate frame in the object coordinate frame. In other words it transforms a point in the world frame to the object frame.

Returns:
oTw

Definition at line 203 of file Pose3d.h.

double isam::Pose3d::pitch ( ) const [inline]

Definition at line 117 of file Pose3d.h.

double isam::Pose3d::roll ( ) const [inline]

Definition at line 118 of file Pose3d.h.

Rot3d isam::Pose3d::rot ( ) const [inline]

Definition at line 121 of file Pose3d.h.

void isam::Pose3d::set ( double  x,
double  y,
double  z,
double  yaw,
double  pitch,
double  roll 
) [inline]

Definition at line 146 of file Pose3d.h.

void isam::Pose3d::set ( const Vector6d v) [inline]

Definition at line 151 of file Pose3d.h.

void isam::Pose3d::set_pitch ( double  pitch) [inline]

Definition at line 127 of file Pose3d.h.

void isam::Pose3d::set_roll ( double  roll) [inline]

Definition at line 128 of file Pose3d.h.

void isam::Pose3d::set_x ( double  x) [inline]

Definition at line 123 of file Pose3d.h.

void isam::Pose3d::set_y ( double  y) [inline]

Definition at line 124 of file Pose3d.h.

void isam::Pose3d::set_yaw ( double  yaw) [inline]

Definition at line 126 of file Pose3d.h.

void isam::Pose3d::set_z ( double  z) [inline]

Definition at line 125 of file Pose3d.h.

Point3d isam::Pose3d::trans ( ) const [inline]

Definition at line 120 of file Pose3d.h.

Point3dh isam::Pose3d::transform_from ( const Point3dh p) const [inline]

Project point from this coordinate frame.

Parameters:
pPoint to project
Returns:
Point p is expressed in the global frame.

Definition at line 260 of file Pose3d.h.

Point3d isam::Pose3d::transform_from ( const Point3d p) const [inline]

Project point from this coordinate frame.

Parameters:
pPoint to project
Returns:
Point p is expressed in the global frame.

Definition at line 269 of file Pose3d.h.

Point3dh isam::Pose3d::transform_to ( const Point3dh p) const [inline]

Project point into this coordinate frame.

Parameters:
pPoint to project
Returns:
Point p locally expressed in this frame.

Definition at line 241 of file Pose3d.h.

Point3d isam::Pose3d::transform_to ( const Point3d p) const [inline]

Project point into this coordinate frame.

Parameters:
pPoint to project
Returns:
Point p locally expressed in this frame.

Definition at line 251 of file Pose3d.h.

Vector6d isam::Pose3d::vector ( ) const [inline]

Definition at line 137 of file Pose3d.h.

void isam::Pose3d::write ( std::ostream &  out) const [inline]

Definition at line 168 of file Pose3d.h.

Eigen::Matrix4d isam::Pose3d::wTo ( ) const [inline]

Convert Pose3 to homogeneous 4x4 transformation matrix. The returned matrix is the object coordinate frame in the world coordinate frame. In other words it transforms a point in the object frame to the world frame.

Returns:
wTo

Definition at line 187 of file Pose3d.h.

double isam::Pose3d::x ( ) const [inline]

Definition at line 113 of file Pose3d.h.

double isam::Pose3d::y ( ) const [inline]

Definition at line 114 of file Pose3d.h.

double isam::Pose3d::yaw ( ) const [inline]

Definition at line 116 of file Pose3d.h.

double isam::Pose3d::z ( ) const [inline]

Definition at line 115 of file Pose3d.h.


Friends And Related Function Documentation

std::ostream& operator<< ( std::ostream &  out,
const Pose3d p 
) [friend]

Definition at line 70 of file Pose3d.h.


Member Data Documentation

Definition at line 76 of file Pose3d.h.

Definition at line 75 of file Pose3d.h.

EIGEN_MAKE_ALIGNED_OPERATOR_NEW const int isam::Pose3d::dim = 6 [static]

Definition at line 80 of file Pose3d.h.


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


demo_lidar
Author(s): Ji Zhang
autogenerated on Fri Jan 3 2014 11:17:40