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;
96 bool equals(
const Pose3& pose,
double tol = 1e-9)
const;
108 Pose3 inverse()
const;
112 return Pose3(R_ * T.R_, t_ + R_ * T.t_);
129 Matrix6 AdjointMap()
const;
136 return AdjointMap() * xi_b;
154 static Matrix6 adjointMap(
const Vector6 &xi);
159 static Vector6 adjoint(
const Vector6 &xi,
const Vector6 &y,
163 static Matrix6 adjointMap_(
const Vector6 &xi) {
return adjointMap(xi);}
164 static Vector6 adjoint_(
const Vector6 &xi,
const Vector6 &y) {
return adjoint(xi, y);}
169 static Vector6 adjointTranspose(
const Vector6& xi,
const Vector6& y,
170 OptionalJacobian<6, 6> H = boost::none);
173 static Matrix6 ExpmapDerivative(
const Vector6& xi);
176 static Matrix6 LogmapDerivative(
const Pose3& xi);
180 static Pose3 Retract(
const Vector6& v, ChartJacobian H = boost::none);
181 static Vector6 Local(
const Pose3& r, ChartJacobian H = boost::none);
193 static Matrix
wedge(
double wx,
double wy,
double wz,
double vx,
double vy,
195 return (Matrix(4, 4) << 0., -wz, wy, vx, wz, 0., -wx, vy, -wy, wx, 0., vz, 0., 0., 0., 0.).finished();
214 return transformFrom(p);
253 Matrix4 matrix()
const;
256 Pose3 transformPoseFrom(
const Pose3& pose)
const;
305 return std::make_pair(3, 5);
314 return std::make_pair(0, 2);
319 friend std::ostream &operator<<(std::ostream &os,
const Pose3& p);
321 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 327 return transformFrom(p, Dpose, Dpoint);
329 Point3 transform_to(
const Point3& p,
330 OptionalJacobian<3, 6> Dpose = boost::none,
331 OptionalJacobian<3, 3> Dpoint = boost::none)
const {
332 return transformTo(p, Dpose, Dpoint);
334 Pose3 transform_pose_to(
const Pose3& pose,
335 OptionalJacobian<6, 6> H1 = boost::none,
336 OptionalJacobian<6, 6> H2 = boost::none)
const {
337 return transformPoseTo(pose, H1, H2);
341 Pose3 transform_to(
const Pose3& pose)
const;
347 friend class boost::serialization::access;
348 template<
class Archive>
349 void serialize(Archive & ar,
const unsigned int ) {
350 ar & BOOST_SERIALIZATION_NVP(R_);
351 ar & BOOST_SERIALIZATION_NVP(t_);
355 #ifdef GTSAM_USE_QUATERNIONS 358 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
372 return Pose3::wedge(xi(0), xi(1), xi(2), xi(3), xi(4), xi(5));
375 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 377 GTSAM_EXPORT boost::optional<Pose3> align(
const std::vector<Point3Pair>& baPointPairs);
381 typedef std::vector<Pose3> Pose3Vector;
396 template <
typename T>
Pose3(const Matrix &T)
Constructor from 4*4 matrix.
Definition: Pose3.h:71
double x() const
get x
Definition: Point3.h:108
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:141
Both LieGroupTraits and Testable.
Definition: Lie.h:237
Template to create a binary predicate.
Definition: Testable.h:110
Definition: BearingRange.h:33
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition: OptionalJacobian.h:39
static std::pair< size_t, size_t > translationInterval()
Return the start and end indices (inclusive) of the translation component of the exponential map para...
Definition: Pose3.h:304
A CRTP helper class that implements Lie group methods Prerequisites: methods operator*,...
Definition: Lie.h:36
Definition: BearingRange.h:193
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
double z() const
get z
Definition: Pose3.h:248
static Matrix wedge(double wx, double wy, double wz, double vx, double vy, double vz)
wedge for Pose3:
Definition: Pose3.h:193
double x() const
get x
Definition: Pose3.h:238
static Pose3 identity()
identity for group operation
Definition: Pose3.h:103
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
Vector6 Adjoint(const Vector6 &xi_b) const
FIXME Not tested - marked as incorrect.
Definition: Pose3.h:135
Matrix wedge< Pose3 >(const Vector &xi)
wedge for Pose3:
Definition: Pose3.h:371
Definition: BearingRange.h:179
Definition: BearingRange.h:39
3D rotation represented as a rotation matrix or quaternion
Rot3 Rotation
Pose Concept requirements.
Definition: Pose3.h:41
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
double y() const
get y
Definition: Point3.h:111
Base class and basic functions for Lie types.
Pose3(const Rot3 &R, const Point3 &t)
Construct from R,t.
Definition: Pose3.h:63
double y() const
get y
Definition: Pose3.h:243
Pose3(const Pose3 &pose)
Copy constructor.
Definition: Pose3.h:58
Point2 operator *(double s, const Point2 &p)
multiply with scalar
Definition: Point2.h:170
double z() const
get z
Definition: Point3.h:114
static std::pair< size_t, size_t > rotationInterval()
Return the start and end indices (inclusive) of the rotation component of the exponential map paramet...
Definition: Pose3.h:313
Pose3()
Default constructor is origin.
Definition: Pose3.h:55