Classes | Public Types | Private Member Functions | Private Attributes | Friends | List of all members
gtsam::Pose2 Class Reference

#include <Pose2.h>

Inheritance diagram for gtsam::Pose2:
Inheritance graph
[legend]

Classes

struct  ChartAtOrigin
 

Public Types

typedef Rot2 Rotation
 
typedef Point2 Translation
 
- Public Types inherited from gtsam::LieGroup< Pose2, 3 >
enum  
 
typedef OptionalJacobian< N, NChartJacobian
 
typedef Eigen::Matrix< double, N, NJacobian
 
typedef Eigen::Matrix< double, N, 1 > TangentVector
 

Public Member Functions

Standard Constructors
 Pose2 ()
 
 Pose2 (const Pose2 &pose)
 
 Pose2 (double x, double y, double theta)
 
 Pose2 (double theta, const Point2 &t)
 
 Pose2 (const Rot2 &r, const Point2 &t)
 
 Pose2 (const Matrix &T)
 
Advanced Constructors
 Pose2 (const Vector &v)
 
Testable
GTSAM_EXPORT void print (const std::string &s="") const
 
GTSAM_EXPORT bool equals (const Pose2 &pose, double tol=1e-9) const
 
Group Action on Point2
GTSAM_EXPORT Point2 transformTo (const Point2 &point, OptionalJacobian< 2, 3 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
 
GTSAM_EXPORT Point2 transformFrom (const Point2 &point, OptionalJacobian< 2, 3 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
 
Point2 operator* (const Point2 &point) const
 
Standard Interface
double x () const
 get x More...
 
double y () const
 get y More...
 
double theta () const
 get theta More...
 
const Point2t () const
 translation More...
 
const Rot2r () const
 rotation More...
 
const Point2translation () const
 translation More...
 
const Rot2rotation () const
 rotation More...
 
GTSAM_EXPORT Matrix3 matrix () const
 
GTSAM_EXPORT Rot2 bearing (const Point2 &point, OptionalJacobian< 1, 3 > H1=boost::none, OptionalJacobian< 1, 2 > H2=boost::none) const
 
GTSAM_EXPORT Rot2 bearing (const Pose2 &pose, OptionalJacobian< 1, 3 > H1=boost::none, OptionalJacobian< 1, 3 > H2=boost::none) const
 
GTSAM_EXPORT double range (const Point2 &point, OptionalJacobian< 1, 3 > H1=boost::none, OptionalJacobian< 1, 2 > H2=boost::none) const
 
GTSAM_EXPORT double range (const Pose2 &point, OptionalJacobian< 1, 3 > H1=boost::none, OptionalJacobian< 1, 3 > H2=boost::none) const
 
- Public Member Functions inherited from gtsam::LieGroup< Pose2, 3 >
Pose2 between (const Pose2 &g) const
 
Pose2 between (const Pose2 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 
Pose2 compose (const Pose2 &g) const
 
Pose2 compose (const Pose2 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 
const Pose2derived () const
 
Pose2 expmap (const TangentVector &v) const
 
Pose2 expmap (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const
 expmap with optional derivatives More...
 
Pose2 inverse (ChartJacobian H) const
 
TangentVector localCoordinates (const Pose2 &g) const
 localCoordinates as required by manifold concept: finds tangent vector between *this and g More...
 
TangentVector localCoordinates (const Pose2 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 localCoordinates with optional derivatives More...
 
TangentVector logmap (const Pose2 &g) const
 
TangentVector logmap (const Pose2 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 logmap with optional derivatives More...
 
Pose2 retract (const TangentVector &v) const
 retract as required by manifold concept: applies v at *this More...
 
Pose2 retract (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const
 retract with optional derivatives More...
 

Private Member Functions

template<class Archive >
void serialize (Archive &ar, const unsigned int)
 

Private Attributes

Rot2 r_
 
Point2 t_
 

Friends

class boost::serialization::access
 

Group

GTSAM_EXPORT Pose2 inverse () const
 inverse More...
 
Pose2 operator* (const Pose2 &p2) const
 compose syntactic sugar More...
 
static Pose2 identity ()
 identity for group operation More...
 

Lie Group

GTSAM_EXPORT Matrix3 AdjointMap () const
 
Vector3 Adjoint (const Vector3 &xi) const
 Apply AdjointMap to twist xi. More...
 
static GTSAM_EXPORT Pose2 Expmap (const Vector3 &xi, ChartJacobian H=boost::none)
 Exponential map at identity - create a rotation from canonical coordinates $ [T_x,T_y,\theta] $. More...
 
static GTSAM_EXPORT Vector3 Logmap (const Pose2 &p, ChartJacobian H=boost::none)
 Log map at identity - return the canonical coordinates $ [T_x,T_y,\theta] $ of this rotation. More...
 
static GTSAM_EXPORT Matrix3 adjointMap (const Vector3 &v)
 
static Vector3 adjoint (const Vector3 &xi, const Vector3 &y)
 
static Vector3 adjointTranspose (const Vector3 &xi, const Vector3 &y)
 
static Matrix3 adjointMap_ (const Vector3 &xi)
 
static Vector3 adjoint_ (const Vector3 &xi, const Vector3 &y)
 
static Matrix3 wedge (double vx, double vy, double w)
 
static GTSAM_EXPORT Matrix3 ExpmapDerivative (const Vector3 &v)
 Derivative of Expmap. More...
 
static GTSAM_EXPORT Matrix3 LogmapDerivative (const Pose2 &v)
 Derivative of Logmap. More...
 

Advanced Interface

GTSAM_EXPORT friend std::ostream & operator<< (std::ostream &os, const Pose2 &p)
 Output stream operator. More...
 
static std::pair< size_t, size_ttranslationInterval ()
 
static std::pair< size_t, size_trotationInterval ()
 

Additional Inherited Members

- Static Public Member Functions inherited from gtsam::LieGroup< Pose2, 3 >
static TangentVector LocalCoordinates (const Pose2 &g)
 LocalCoordinates at origin: possible in Lie group because it has an identity. More...
 
static TangentVector LocalCoordinates (const Pose2 &g, ChartJacobian H)
 LocalCoordinates at origin with optional derivative. More...
 
static Pose2 Retract (const TangentVector &v)
 Retract at origin: possible in Lie group because it has an identity. More...
 
static Pose2 Retract (const TangentVector &v, ChartJacobian H)
 Retract at origin with optional derivative. More...
 

Detailed Description

Definition at line 36 of file Pose2.h.

Member Typedef Documentation

Pose Concept requirements

Definition at line 41 of file Pose2.h.

Definition at line 42 of file Pose2.h.

Constructor & Destructor Documentation

gtsam::Pose2::Pose2 ( )
inline

default constructor = origin

Definition at line 55 of file Pose2.h.

gtsam::Pose2::Pose2 ( const Pose2 pose)
inline

copy constructor

Definition at line 60 of file Pose2.h.

gtsam::Pose2::Pose2 ( double  x,
double  y,
double  theta 
)
inline

construct from (x,y,theta)

Parameters
xx coordinate
yy coordinate
thetaangle with positive X-axis

Definition at line 68 of file Pose2.h.

gtsam::Pose2::Pose2 ( double  theta,
const Point2 t 
)
inline

construct from rotation and translation

Definition at line 73 of file Pose2.h.

gtsam::Pose2::Pose2 ( const Rot2 r,
const Point2 t 
)
inline

construct from r,t

Definition at line 78 of file Pose2.h.

gtsam::Pose2::Pose2 ( const Matrix T)
inline

Constructor from 3*3 matrix

Definition at line 81 of file Pose2.h.

gtsam::Pose2::Pose2 ( const Vector v)
inline

Construct from canonical coordinates $ [T_x,T_y,\theta] $ (Lie algebra)

Definition at line 91 of file Pose2.h.

Member Function Documentation

Vector3 gtsam::Pose2::Adjoint ( const Vector3 xi) const
inline

Apply AdjointMap to twist xi.

Definition at line 137 of file Pose2.h.

static Vector3 gtsam::Pose2::adjoint ( const Vector3 xi,
const Vector3 y 
)
inlinestatic

Action of the adjointMap on a Lie-algebra vector y, with optional derivatives

Definition at line 149 of file Pose2.h.

static Vector3 gtsam::Pose2::adjoint_ ( const Vector3 xi,
const Vector3 y 
)
inlinestatic

Definition at line 162 of file Pose2.h.

Matrix3 gtsam::Pose2::AdjointMap ( ) const

Calculate Adjoint map Ad_pose is 3*3 matrix that when applied to twist xi $ [T_x,T_y,\theta] $, returns Ad_pose(xi)

Definition at line 126 of file Pose2.cpp.

Matrix3 gtsam::Pose2::adjointMap ( const Vector3 v)
static

Compute the [ad(w,v)] operator for SE2 as in [Kobilarov09siggraph], pg 19

Definition at line 137 of file Pose2.cpp.

static Matrix3 gtsam::Pose2::adjointMap_ ( const Vector3 xi)
inlinestatic

Definition at line 161 of file Pose2.h.

static Vector3 gtsam::Pose2::adjointTranspose ( const Vector3 xi,
const Vector3 y 
)
inlinestatic

The dual version of adjoint action, acting on the dual space of the Lie-algebra vector space.

Definition at line 156 of file Pose2.h.

Rot2 gtsam::Pose2::bearing ( const Point2 point,
OptionalJacobian< 1, 3 >  H1 = boost::none,
OptionalJacobian< 1, 2 >  H2 = boost::none 
) const

Calculate bearing to a landmark

Parameters
point2D location of landmark
Returns
2D rotation $ \in SO(2) $

Definition at line 228 of file Pose2.cpp.

Rot2 gtsam::Pose2::bearing ( const Pose2 pose,
OptionalJacobian< 1, 3 >  H1 = boost::none,
OptionalJacobian< 1, 3 >  H2 = boost::none 
) const

Calculate bearing to another pose

Parameters
pointSO(2) location of other pose
Returns
2D rotation $ \in SO(2) $

Definition at line 242 of file Pose2.cpp.

bool gtsam::Pose2::equals ( const Pose2 pose,
double  tol = 1e-9 
) const

assert equality up to a tolerance

Definition at line 61 of file Pose2.cpp.

Pose2 gtsam::Pose2::Expmap ( const Vector3 xi,
ChartJacobian  H = boost::none 
)
static

Exponential map at identity - create a rotation from canonical coordinates $ [T_x,T_y,\theta] $.

Definition at line 66 of file Pose2.cpp.

Matrix3 gtsam::Pose2::ExpmapDerivative ( const Vector3 v)
static

Derivative of Expmap.

Definition at line 148 of file Pose2.cpp.

static Pose2 gtsam::Pose2::identity ( )
inlinestatic

identity for group operation

Definition at line 110 of file Pose2.h.

Pose2 gtsam::Pose2::inverse ( ) const

inverse

Definition at line 201 of file Pose2.cpp.

Vector3 gtsam::Pose2::Logmap ( const Pose2 p,
ChartJacobian  H = boost::none 
)
static

Log map at identity - return the canonical coordinates $ [T_x,T_y,\theta] $ of this rotation.

Definition at line 82 of file Pose2.cpp.

Matrix3 gtsam::Pose2::LogmapDerivative ( const Pose2 v)
static

Derivative of Logmap.

Definition at line 179 of file Pose2.cpp.

Matrix3 gtsam::Pose2::matrix ( ) const

Definition at line 36 of file Pose2.cpp.

Pose2 gtsam::Pose2::operator* ( const Pose2 p2) const
inline

compose syntactic sugar

Definition at line 116 of file Pose2.h.

Point2 gtsam::Pose2::operator* ( const Point2 point) const
inline

syntactic sugar for transformFrom

Definition at line 208 of file Pose2.h.

void gtsam::Pose2::print ( const std::string &  s = "") const

print with optional string

Definition at line 50 of file Pose2.cpp.

const Rot2& gtsam::Pose2::r ( ) const
inline

rotation

Definition at line 227 of file Pose2.h.

double gtsam::Pose2::range ( const Point2 point,
OptionalJacobian< 1, 3 >  H1 = boost::none,
OptionalJacobian< 1, 2 >  H2 = boost::none 
) const

Calculate range to a landmark

Parameters
point2D location of landmark
Returns
range (double)

Definition at line 253 of file Pose2.cpp.

double gtsam::Pose2::range ( const Pose2 point,
OptionalJacobian< 1, 3 >  H1 = boost::none,
OptionalJacobian< 1, 3 >  H2 = boost::none 
) const

Calculate range to another pose

Parameters
point2D location of other pose
Returns
range (double)

Definition at line 270 of file Pose2.cpp.

const Rot2& gtsam::Pose2::rotation ( ) const
inline

rotation

Definition at line 233 of file Pose2.h.

static std::pair<size_t, size_t> gtsam::Pose2::rotationInterval ( )
inlinestatic

Return the start and end indices (inclusive) of the rotation component of the exponential map parameterization

Returns
a pair of [start, end] indices into the tangent space vector

Definition at line 288 of file Pose2.h.

template<class Archive >
void gtsam::Pose2::serialize ( Archive &  ar,
const unsigned  int 
)
inlineprivate

Definition at line 301 of file Pose2.h.

const Point2& gtsam::Pose2::t ( ) const
inline

translation

Definition at line 224 of file Pose2.h.

double gtsam::Pose2::theta ( ) const
inline

get theta

Definition at line 221 of file Pose2.h.

Point2 gtsam::Pose2::transformFrom ( const Point2 point,
OptionalJacobian< 2, 3 >  Dpose = boost::none,
OptionalJacobian< 2, 2 >  Dpoint = boost::none 
) const

Return point coordinates in global frame

Definition at line 218 of file Pose2.cpp.

Point2 gtsam::Pose2::transformTo ( const Point2 point,
OptionalJacobian< 2, 3 >  Dpose = boost::none,
OptionalJacobian< 2, 2 >  Dpoint = boost::none 
) const

Return point coordinates in pose coordinate frame

Definition at line 207 of file Pose2.cpp.

const Point2& gtsam::Pose2::translation ( ) const
inline

translation

Definition at line 230 of file Pose2.h.

static std::pair<size_t, size_t> gtsam::Pose2::translationInterval ( )
inlinestatic

Return the start and end indices (inclusive) of the translation component of the exponential map parameterization

Returns
a pair of [start, end] indices into the tangent space vector

Definition at line 281 of file Pose2.h.

static Matrix3 gtsam::Pose2::wedge ( double  vx,
double  vy,
double  w 
)
inlinestatic

wedge for SE(2):

Parameters
xi3-dim twist (v,omega) where omega is angular velocity v (vx,vy) = 2D velocity
Returns
xihat, 3*3 element of Lie algebra that can be exponentiated

Definition at line 171 of file Pose2.h.

double gtsam::Pose2::x ( ) const
inline

get x

Definition at line 215 of file Pose2.h.

double gtsam::Pose2::y ( ) const
inline

get y

Definition at line 218 of file Pose2.h.

Friends And Related Function Documentation

friend class boost::serialization::access
friend

Definition at line 299 of file Pose2.h.

GTSAM_EXPORT friend std::ostream& operator<< ( std::ostream &  os,
const Pose2 p 
)
friend

Output stream operator.

Definition at line 55 of file Pose2.cpp.

Member Data Documentation

Rot2 gtsam::Pose2::r_
private

Definition at line 46 of file Pose2.h.

Point2 gtsam::Pose2::t_
private

Definition at line 47 of file Pose2.h.


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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:23