gtsam  4.0.0
gtsam
gtsam::Pose2 Class Reference
+ Inheritance diagram for gtsam::Pose2:

Group

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

Lie Group

Matrix3 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)
 
Vector3 Adjoint (const Vector3 &xi) const
 Apply AdjointMap to twist xi.
 
static Pose2 Expmap (const Vector3 &xi, ChartJacobian H=boost::none)
 Exponential map at identity - create a rotation from canonical coordinates \( [T_x,T_y,\theta] \).
 
static 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.
 
static Matrix3 adjointMap (const Vector3 &v)
 Compute the [ad(w,v)] operator for SE2 as in [Kobilarov09siggraph], pg 19.
 
static Vector3 adjoint (const Vector3 &xi, const Vector3 &y)
 Action of the adjointMap on a Lie-algebra vector y, with optional derivatives.
 
static Vector3 adjointTranspose (const Vector3 &xi, const Vector3 &y)
 The dual version of adjoint action, acting on the dual space of the Lie-algebra vector space.
 
static Matrix3 adjointMap_ (const Vector3 &xi)
 
static Vector3 adjoint_ (const Vector3 &xi, const Vector3 &y)
 
static Matrix3 wedge (double vx, double vy, double w)
 wedge for SE(2): More...
 
static Matrix3 ExpmapDerivative (const Vector3 &v)
 Derivative of Expmap.
 
static Matrix3 LogmapDerivative (const Pose2 &v)
 Derivative of Logmap.
 

Public Member Functions

Standard Constructors
 Pose2 ()
 default constructor = origin
 
 Pose2 (const Pose2 &pose)
 copy constructor
 
 Pose2 (double x, double y, double theta)
 construct from (x,y,theta) More...
 
 Pose2 (double theta, const Point2 &t)
 construct from rotation and translation
 
 Pose2 (const Rot2 &r, const Point2 &t)
 construct from r,t
 
 Pose2 (const Matrix &T)
 Constructor from 3*3 matrix.
 
Advanced Constructors
 Pose2 (const Vector &v)
 Construct from canonical coordinates \( [T_x,T_y,\theta] \) (Lie algebra)
 
Testable
void print (const std::string &s="") const
 print with optional string
 
bool equals (const Pose2 &pose, double tol=1e-9) const
 assert equality up to a tolerance
 
Group Action on Point2
Point2 transformTo (const Point2 &point, OptionalJacobian< 2, 3 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
 Return point coordinates in pose coordinate frame.
 
Point2 transformFrom (const Point2 &point, OptionalJacobian< 2, 3 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
 Return point coordinates in global frame.
 
Point2 operator * (const Point2 &point) const
 syntactic sugar for transformFrom
 
Standard Interface
double x () const
 get x
 
double y () const
 get y
 
double theta () const
 get theta
 
const Point2t () const
 translation
 
const Rot2r () const
 rotation
 
const Point2translation () const
 translation
 
const Rot2rotation () const
 rotation
 
Matrix3 matrix () const
 
Rot2 bearing (const Point2 &point, OptionalJacobian< 1, 3 > H1=boost::none, OptionalJacobian< 1, 2 > H2=boost::none) const
 Calculate bearing to a landmark. More...
 
Rot2 bearing (const Pose2 &pose, OptionalJacobian< 1, 3 > H1=boost::none, OptionalJacobian< 1, 3 > H2=boost::none) const
 Calculate bearing to another pose. More...
 
double range (const Point2 &point, OptionalJacobian< 1, 3 > H1=boost::none, OptionalJacobian< 1, 2 > H2=boost::none) const
 Calculate range to a landmark. More...
 
double range (const Pose2 &point, OptionalJacobian< 1, 3 > H1=boost::none, OptionalJacobian< 1, 3 > H2=boost::none) const
 Calculate range to another pose. More...
 
- Public Member Functions inherited from gtsam::LieGroup< Pose2, 3 >
 BOOST_STATIC_ASSERT_MSG (N !=Eigen::Dynamic, "LieGroup not yet specialized for dynamically sized types.")
 
const Pose2derived () const
 
Pose2 compose (const Pose2 &g) const
 
Pose2 compose (const Pose2 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 
Pose2 between (const Pose2 &g) const
 
Pose2 between (const Pose2 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 
Pose2 inverse (ChartJacobian H) const
 
Pose2 expmap (const TangentVector &v) const
 expmap as required by manifold concept Applies exponential map to v and composes with *this
 
Pose2 expmap (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const
 expmap with optional derivatives
 
TangentVector logmap (const Pose2 &g) const
 logmap as required by manifold concept Applies logarithmic map to group element that takes *this to g
 
TangentVector logmap (const Pose2 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 logmap with optional derivatives
 
Pose2 retract (const TangentVector &v) const
 retract as required by manifold concept: applies v at *this
 
Pose2 retract (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const
 retract with optional derivatives
 
TangentVector localCoordinates (const Pose2 &g) const
 localCoordinates as required by manifold concept: finds tangent vector between *this and g
 
TangentVector localCoordinates (const Pose2 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 localCoordinates with optional derivatives
 

Static Public Member Functions

Advanced Interface
static std::pair< size_t, size_t > translationInterval ()
 Return the start and end indices (inclusive) of the translation component of the exponential map parameterization. More...
 
static std::pair< size_t, size_t > rotationInterval ()
 Return the start and end indices (inclusive) of the rotation component of the exponential map parameterization. More...
 
- Static Public Member Functions inherited from gtsam::LieGroup< Pose2, 3 >
static Pose2 Retract (const TangentVector &v)
 Retract at origin: possible in Lie group because it has an identity.
 
static Pose2 Retract (const TangentVector &v, ChartJacobian H)
 Retract at origin with optional derivative.
 
static TangentVector LocalCoordinates (const Pose2 &g)
 LocalCoordinates at origin: possible in Lie group because it has an identity.
 
static TangentVector LocalCoordinates (const Pose2 &g, ChartJacobian H)
 LocalCoordinates at origin with optional derivative.
 

Public Types

typedef Rot2 Rotation
 Pose Concept requirements.
 
typedef Point2 Translation
 
- Public Types inherited from gtsam::LieGroup< Pose2, 3 >
enum  
 
typedef OptionalJacobian< N, N > ChartJacobian
 
typedef Eigen::Matrix< double, N, N > Jacobian
 
typedef Eigen::Matrix< double, N, 1 > TangentVector
 

Classes

struct  ChartAtOrigin
 

Friends

class boost::serialization::access
 

Constructor & Destructor Documentation

◆ Pose2()

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

Member Function Documentation

◆ bearing() [1/2]

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) \)

◆ bearing() [2/2]

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) \)

◆ range() [1/2]

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)

◆ range() [2/2]

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)

◆ rotationInterval()

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

◆ translationInterval()

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

◆ wedge()

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

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