#include <Pose3.h>
Classes | |
struct | ChartAtOrigin |
Public Types | |
typedef Rot3 | Rotation |
typedef Point3 | Translation |
Public Types inherited from gtsam::LieGroup< Pose3, 6 > | |
typedef OptionalJacobian< N, N > | ChartJacobian |
typedef Eigen::Matrix< double, N, N > | Jacobian |
typedef Eigen::Matrix< double, N, 1 > | TangentVector |
Private Attributes | |
Rot3 | R_ |
Rotation gRp, between global and pose frame. More... | |
Point3 | t_ |
Translation gPp, from global origin to pose frame origin. More... | |
Standard Constructors | |
Pose3 () | |
Pose3 (const Pose3 &pose) | |
Pose3 (const Rot3 &R, const Point3 &t) | |
Pose3 (const Pose2 &pose2) | |
Pose3 (const Matrix &T) | |
static Pose3 | Create (const Rot3 &R, const Point3 &t, OptionalJacobian< 6, 3 > HR={}, OptionalJacobian< 6, 3 > Ht={}) |
Named constructor with derivatives. More... | |
static std::optional< Pose3 > | Align (const Point3Pairs &abPointPairs) |
static std::optional< Pose3 > | Align (const Matrix &a, const Matrix &b) |
Testable | |
void | print (const std::string &s="") const |
print with optional string More... | |
bool | equals (const Pose3 &pose, double tol=1e-9) const |
assert equality up to a tolerance More... | |
Group | |
Pose3 | inverse () const |
inverse transformation with derivatives More... | |
Pose3 | operator* (const Pose3 &T) const |
compose syntactic sugar More... | |
Pose3 | interpolateRt (const Pose3 &T, double t) const |
static Pose3 | Identity () |
identity for group operation More... | |
Lie Group | |
Matrix6 | AdjointMap () const |
Vector6 | Adjoint (const Vector6 &xi_b, OptionalJacobian< 6, 6 > H_this={}, OptionalJacobian< 6, 6 > H_xib={}) const |
Vector6 | AdjointTranspose (const Vector6 &x, OptionalJacobian< 6, 6 > H_this={}, OptionalJacobian< 6, 6 > H_x={}) const |
The dual version of Adjoint. More... | |
static Pose3 | Expmap (const Vector6 &xi, OptionalJacobian< 6, 6 > Hxi={}) |
Exponential map at identity - create a rotation from canonical coordinates . More... | |
static Vector6 | Logmap (const Pose3 &pose, OptionalJacobian< 6, 6 > Hpose={}) |
Log map at identity - return the canonical coordinates of this rotation. More... | |
static Matrix6 | adjointMap (const Vector6 &xi) |
static Vector6 | adjoint (const Vector6 &xi, const Vector6 &y, OptionalJacobian< 6, 6 > Hxi={}, OptionalJacobian< 6, 6 > H_y={}) |
static Matrix6 | adjointMap_ (const Vector6 &xi) |
static Vector6 | adjoint_ (const Vector6 &xi, const Vector6 &y) |
static Vector6 | adjointTranspose (const Vector6 &xi, const Vector6 &y, OptionalJacobian< 6, 6 > Hxi={}, OptionalJacobian< 6, 6 > H_y={}) |
static Matrix6 | ExpmapDerivative (const Vector6 &xi) |
Derivative of Expmap. More... | |
static Matrix6 | LogmapDerivative (const Pose3 &xi) |
Derivative of Logmap. More... | |
static Matrix3 | ComputeQforExpmapDerivative (const Vector6 &xi, double nearZeroThreshold=1e-5) |
static Vector3 | ExpmapTranslation (const Vector3 &w, const Vector3 &v, OptionalJacobian< 3, 3 > Q={}, OptionalJacobian< 3, 3 > J={}, double nearZeroThreshold=1e-5) |
static Matrix | wedge (double wx, double wy, double wz, double vx, double vy, double vz) |
Group Action on Point3 | |
Point3 | transformFrom (const Point3 &point, OptionalJacobian< 3, 6 > Hself={}, OptionalJacobian< 3, 3 > Hpoint={}) const |
takes point in Pose coordinates and transforms it to world coordinates More... | |
Matrix | transformFrom (const Matrix &points) const |
transform many points in Pose coordinates and transform to world. More... | |
Point3 | operator* (const Point3 &point) const |
Point3 | transformTo (const Point3 &point, OptionalJacobian< 3, 6 > Hself={}, OptionalJacobian< 3, 3 > Hpoint={}) const |
takes point in world coordinates and transforms it to Pose coordinates More... | |
Matrix | transformTo (const Matrix &points) const |
transform many points in world coordinates and transform to Pose. More... | |
Standard Interface | |
const Rot3 & | rotation (OptionalJacobian< 3, 6 > Hself={}) const |
get rotation More... | |
const Point3 & | translation (OptionalJacobian< 3, 6 > Hself={}) const |
get translation More... | |
double | x () const |
get x More... | |
double | y () const |
get y More... | |
double | z () const |
get z More... | |
Matrix4 | matrix () const |
Pose3 | transformPoseFrom (const Pose3 &aTb, OptionalJacobian< 6, 6 > Hself={}, OptionalJacobian< 6, 6 > HaTb={}) const |
Pose3 | transformPoseTo (const Pose3 &wTb, OptionalJacobian< 6, 6 > Hself={}, OptionalJacobian< 6, 6 > HwTb={}) const |
double | range (const Point3 &point, OptionalJacobian< 1, 6 > Hself={}, OptionalJacobian< 1, 3 > Hpoint={}) const |
double | range (const Pose3 &pose, OptionalJacobian< 1, 6 > Hself={}, OptionalJacobian< 1, 6 > Hpose={}) const |
Unit3 | bearing (const Point3 &point, OptionalJacobian< 2, 6 > Hself={}, OptionalJacobian< 2, 3 > Hpoint={}) const |
Unit3 | bearing (const Pose3 &pose, OptionalJacobian< 2, 6 > Hself={}, OptionalJacobian< 2, 6 > Hpose={}) const |
Advanced Interface | |
Pose3 | slerp (double t, const Pose3 &other, OptionalJacobian< 6, 6 > Hx={}, OptionalJacobian< 6, 6 > Hy={}) const |
Spherical Linear interpolation between *this and other. More... | |
static std::pair< size_t, size_t > | translationInterval () |
static std::pair< size_t, size_t > | rotationInterval () |
GTSAM_EXPORT friend std::ostream & | operator<< (std::ostream &os, const Pose3 &p) |
Output stream operator. More... | |
Additional Inherited Members | |
Public Member Functions inherited from gtsam::LieGroup< Pose3, 6 > | |
Pose3 | between (const Pose3 &g) const |
Pose3 | between (const Pose3 &g, ChartJacobian H1, ChartJacobian H2={}) const |
SOn | between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
GTSAM_EXPORT SOn | between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
Pose3 | compose (const Pose3 &g) const |
Pose3 | compose (const Pose3 &g, ChartJacobian H1, ChartJacobian H2={}) const |
SOn | compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
GTSAM_EXPORT SOn | compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
const Pose3 & | derived () const |
Pose3 | expmap (const TangentVector &v) const |
Pose3 | expmap (const TangentVector &v, ChartJacobian H1, ChartJacobian H2={}) const |
expmap with optional derivatives More... | |
Pose3 | inverse (ChartJacobian H) const |
TangentVector | localCoordinates (const Pose3 &g) const |
localCoordinates as required by manifold concept: finds tangent vector between *this and g More... | |
TangentVector | localCoordinates (const Pose3 &g, ChartJacobian H1, ChartJacobian H2={}) const |
localCoordinates with optional derivatives More... | |
TangentVector | logmap (const Pose3 &g) const |
TangentVector | logmap (const Pose3 &g, ChartJacobian H1, ChartJacobian H2={}) const |
logmap with optional derivatives More... | |
Pose3 | retract (const TangentVector &v) const |
retract as required by manifold concept: applies v at *this More... | |
Pose3 | retract (const TangentVector &v, ChartJacobian H1, ChartJacobian H2={}) const |
retract with optional derivatives More... | |
Static Public Member Functions inherited from gtsam::LieGroup< Pose3, 6 > | |
static TangentVector | LocalCoordinates (const Pose3 &g) |
LocalCoordinates at origin: possible in Lie group because it has an identity. More... | |
static TangentVector | LocalCoordinates (const Pose3 &g, ChartJacobian H) |
LocalCoordinates at origin with optional derivative. More... | |
static Pose3 | Retract (const TangentVector &v) |
Retract at origin: possible in Lie group because it has an identity. More... | |
static Pose3 | Retract (const TangentVector &v, ChartJacobian H) |
Retract at origin with optional derivative. More... | |
Static Public Attributes inherited from gtsam::LieGroup< Pose3, 6 > | |
constexpr static auto | dimension |
typedef Rot3 gtsam::Pose3::Rotation |
typedef Point3 gtsam::Pose3::Translation |
|
inline |
|
explicit |
|
inline |
|
static |
Vector6 Pose3::Adjoint | ( | const Vector6 & | xi_b, |
OptionalJacobian< 6, 6 > | H_this = {} , |
||
OptionalJacobian< 6, 6 > | H_xib = {} |
||
) | const |
Apply this pose's AdjointMap Ad_g to a twist , i.e. a body-fixed velocity, transforming it to the spatial frame Note that H_xib = AdjointMap()
|
inlinestatic |
Matrix6 Pose3::AdjointMap | ( | ) | const |
|
static |
Compute the [ad(w,v)] operator as defined in [Kobilarov09siggraph], pg 11 [ad(w,v)] = [w^, zero3; v^, w^] Note that this is the matrix representation of the adjoint operator for se3 Lie algebra, aka the Lie bracket, and also the derivative of Adjoint map for the Lie group SE3.
Let be the se3 Lie algebra, and be its vector representation. We have the following relationship:
We use this to compute the discrete version of the inverse right-trivialized tangent map, and its inverse transpose in the discrete Euler Poincare' (DEP) operator.
|
inlinestatic |
Vector6 Pose3::AdjointTranspose | ( | const Vector6 & | x, |
OptionalJacobian< 6, 6 > | H_this = {} , |
||
OptionalJacobian< 6, 6 > | H_x = {} |
||
) | const |
|
static |
|
static |
Unit3 Pose3::bearing | ( | const Point3 & | point, |
OptionalJacobian< 2, 6 > | Hself = {} , |
||
OptionalJacobian< 2, 3 > | Hpoint = {} |
||
) | const |
Unit3 Pose3::bearing | ( | const Pose3 & | pose, |
OptionalJacobian< 2, 6 > | Hself = {} , |
||
OptionalJacobian< 2, 6 > | Hpose = {} |
||
) | const |
|
static |
Compute the 3x3 bottom-left block Q of SE3 Expmap right derivative matrix J_r(xi) = [J_(w) Z_3x3; Q_r J_(w)] where J_(w) is the SO3 Expmap right derivative. (see Chirikjian11book2, pg 44, eq 10.95. The closed-form formula is identical to formula 102 in Barfoot14tro where Q_l of the SE3 Expmap left derivative matrix is given. This is the Jacobian of ExpmapTranslation and computed there.
|
static |
|
static |
|
static |
|
static |
Compute the translation part of the exponential map, with Jacobians.
w | 3D angular velocity |
v | 3D velocity |
Q | Optionally, compute 3x3 Jacobian wrpt w |
J | Optionally, compute 3x3 Jacobian wrpt v = right Jacobian of SO(3) |
nearZeroThreshold | threshold for small values |
|
inlinestatic |
Interpolate between two poses via individual rotation and translation interpolation.
The default "interpolate" method defined in Lie.h minimizes the geodesic distance on the manifold, leading to a screw motion interpolation in Cartesian space, which might not be what is expected. In contrast, this method executes a straight line interpolation for the translation, while still using interpolate (aka "slerp") for the rotational component. This might be more intuitive in many applications.
T | End point of interpolation. |
t | A value in [0, 1]. |
Pose3 Pose3::inverse | ( | ) | const |
|
static |
|
static |
void Pose3::print | ( | const std::string & | s = "" | ) | const |
double Pose3::range | ( | const Point3 & | point, |
OptionalJacobian< 1, 6 > | Hself = {} , |
||
OptionalJacobian< 1, 3 > | Hpoint = {} |
||
) | const |
double Pose3::range | ( | const Pose3 & | pose, |
OptionalJacobian< 1, 6 > | Hself = {} , |
||
OptionalJacobian< 1, 6 > | Hpose = {} |
||
) | const |
const Rot3 & Pose3::rotation | ( | OptionalJacobian< 3, 6 > | Hself = {} | ) | const |
Pose3 Pose3::slerp | ( | double | t, |
const Pose3 & | other, | ||
OptionalJacobian< 6, 6 > | Hx = {} , |
||
OptionalJacobian< 6, 6 > | Hy = {} |
||
) | const |
Point3 Pose3::transformFrom | ( | const Point3 & | point, |
OptionalJacobian< 3, 6 > | Hself = {} , |
||
OptionalJacobian< 3, 3 > | Hpoint = {} |
||
) | const |
Pose3 Pose3::transformPoseFrom | ( | const Pose3 & | aTb, |
OptionalJacobian< 6, 6 > | Hself = {} , |
||
OptionalJacobian< 6, 6 > | HaTb = {} |
||
) | const |
Pose3 Pose3::transformPoseTo | ( | const Pose3 & | wTb, |
OptionalJacobian< 6, 6 > | Hself = {} , |
||
OptionalJacobian< 6, 6 > | HwTb = {} |
||
) | const |
Point3 Pose3::transformTo | ( | const Point3 & | point, |
OptionalJacobian< 3, 6 > | Hself = {} , |
||
OptionalJacobian< 3, 3 > | Hpoint = {} |
||
) | const |
const Point3 & Pose3::translation | ( | OptionalJacobian< 3, 6 > | Hself = {} | ) | const |
|
inlinestatic |
|
friend |
|
private |
|
private |