20 #include <gtsam/config.h> 59 R_(pose.R_), t_(pose.t_) {
72 R_(T(0, 0), T(0, 1), T(0, 2), T(1, 0), T(1, 1), T(1, 2), T(2, 0), T(2, 1),
73 T(2, 2)), t_(T(0, 3), T(1, 3), T(2, 3)) {
86 static boost::optional<Pose3> Align(
const std::vector<Point3Pair>& abPointPairs);
93 void print(
const std::string&
s =
"")
const;
130 return Pose3(interpolate<Rot3>(R_, T.
R_, t),
131 interpolate<Point3>(t_, T.
t_, t));
148 Matrix6 AdjointMap()
const;
155 return AdjointMap() * xi_b;
173 static Matrix6 adjointMap(
const Vector6 &xi);
178 static Vector6
adjoint(
const Vector6 &xi,
const Vector6 &
y,
182 static Matrix6
adjointMap_(
const Vector6 &xi) {
return adjointMap(xi);}
183 static Vector6
adjoint_(
const Vector6 &xi,
const Vector6 &y) {
return adjoint(xi, y);}
188 static Vector6 adjointTranspose(
const Vector6& xi,
const Vector6& y,
192 static Matrix6 ExpmapDerivative(
const Vector6& xi);
195 static Matrix6 LogmapDerivative(
const Pose3& xi);
212 static Matrix3 ComputeQforExpmapDerivative(
213 const Vector6& xi,
double nearZeroThreshold = 1
e-5);
226 return (
Matrix(4, 4) << 0., -wz, wy, vx, wz, 0., -wx, vy, -wy, wx, 0., vz, 0., 0., 0., 0.).finished();
344 return std::make_pair(3, 5);
353 return std::make_pair(0, 2);
362 friend class boost::serialization::access;
363 template<
class Archive>
365 ar & BOOST_SERIALIZATION_NVP(R_);
366 ar & BOOST_SERIALIZATION_NVP(t_);
370 #ifdef GTSAM_USE_QUATERNIONS 410 template <
typename T>
void print(const Matrix &A, const string &s, ostream &stream)
static Matrix6 adjointMap_(const Vector6 &xi)
Point3 t_
Translation gPp, from global origin to pose frame origin.
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Point3 operator*(const Point3 &point) const
Pose3 interpolateRt(const Pose3 &T, double t) const
Rot3_ rotation(const Pose3_ &pose)
void adjoint(const MatrixType &m)
Vector6 Adjoint(const Vector6 &xi_b) const
FIXME Not tested - marked as incorrect.
std::vector< Pose3 > Pose3Vector
Rot3 R_
Rotation gRp, between global and pose frame.
Rot2 R(Rot2::fromAngle(0.1))
Pose2_ Expmap(const Vector3_ &xi)
static Matrix wedge(double wx, double wy, double wz, double vx, double vy, double vz)
std::vector< std::pair< Pose3, Pose3 > > Pose3Pairs
static Pose3 identity()
identity for group operation
Represents a 3D point on a unit sphere.
StridedVectorType vy(make_vector(y,*n, std::abs(*incy)))
Point3_ transformFrom(const Pose3_ &x, const Point3_ &p)
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
static std::pair< size_t, size_t > rotationInterval()
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Pose3(const Rot3 &R, const Point3 &t)
Matrix wedge< Pose3 >(const Vector &xi)
Base class and basic functions for Lie types.
static std::pair< size_t, size_t > translationInterval()
ofstream os("timeSchurFactors.csv")
Both LieGroupTraits and Testable.
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
static Vector6 adjoint_(const Vector6 &xi, const Vector6 &y)
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
StridedVectorType vx(make_vector(x,*n, std::abs(*incx)))
std::pair< Pose3, Pose3 > Pose3Pair
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Pose3 operator*(const Pose3 &T) const
compose syntactic sugar
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
void serialize(Archive &ar, const unsigned int)
3D rotation represented as a rotation matrix or quaternion