|
GTSAM_EXPORT 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 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] \).
|
|
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.
|
|
static GTSAM_EXPORT 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 GTSAM_EXPORT Matrix3 | ExpmapDerivative (const Vector3 &v) |
| Derivative of Expmap.
|
|
static GTSAM_EXPORT Matrix3 | LogmapDerivative (const Pose2 &v) |
| Derivative of Logmap.
|
|
|
|
| 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.
|
|
|
| Pose2 (const Vector &v) |
| Construct from canonical coordinates \( [T_x,T_y,\theta] \) (Lie algebra)
|
|
|
GTSAM_EXPORT void | print (const std::string &s="") const |
| print with optional string
|
|
GTSAM_EXPORT bool | equals (const Pose2 &pose, double tol=1e-9) const |
| assert equality up to a tolerance
|
|
|
GTSAM_EXPORT 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.
|
|
GTSAM_EXPORT 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
|
|
|
double | x () const |
| get x
|
|
double | y () const |
| get y
|
|
double | theta () const |
| get theta
|
|
const Point2 & | t () const |
| translation
|
|
const Rot2 & | r () const |
| rotation
|
|
const Point2 & | translation () const |
| translation
|
|
const Rot2 & | rotation () const |
| rotation
|
|
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 |
| Calculate bearing to a landmark. More...
|
|
GTSAM_EXPORT Rot2 | bearing (const Pose2 &pose, OptionalJacobian< 1, 3 > H1=boost::none, OptionalJacobian< 1, 3 > H2=boost::none) const |
| Calculate bearing to another pose. More...
|
|
GTSAM_EXPORT double | range (const Point2 &point, OptionalJacobian< 1, 3 > H1=boost::none, OptionalJacobian< 1, 2 > H2=boost::none) const |
| Calculate range to a landmark. More...
|
|
GTSAM_EXPORT double | range (const Pose2 &point, OptionalJacobian< 1, 3 > H1=boost::none, OptionalJacobian< 1, 3 > H2=boost::none) const |
| Calculate range to another pose. More...
|
|
const Pose2 & | derived () const |
|
Pose2 | compose (const Pose2 &g) const |
|
Pose2 | compose (const Pose2 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
|
SOn | compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
|
SOn | compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
|
Pose2 | between (const Pose2 &g) const |
|
Pose2 | between (const Pose2 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
|
SOn | between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
|
SOn | between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) 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
|
|