PoseRTV.h 5.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179
  1. /**
  2. * @file PoseRTV.h
  3. * @brief Pose3 with translational velocity
  4. * @author Alex Cunningham
  5. */
  6. #pragma once
  7. #include <gtsam_unstable/dllexport.h>
  8. #include <gtsam/geometry/Pose3.h>
  9. #include <gtsam/base/ProductLieGroup.h>
  10. namespace gtsam {
  11. /// Syntactic sugar to clarify components
  12. typedef Vector3 Velocity3;
  13. /**
  14. * Robot state for use with IMU measurements
  15. * - contains translation, translational velocity and rotation
  16. * TODO(frank): Alex should deprecate/move to project
  17. */
  18. class GTSAM_UNSTABLE_EXPORT PoseRTV : public ProductLieGroup<Pose3,Velocity3> {
  19. protected:
  20. typedef ProductLieGroup<Pose3,Velocity3> Base;
  21. typedef OptionalJacobian<9, 9> ChartJacobian;
  22. public:
  23. // constructors - with partial versions
  24. PoseRTV() {}
  25. PoseRTV(const Point3& t, const Rot3& rot, const Velocity3& vel)
  26. : Base(Pose3(rot, t), vel) {}
  27. PoseRTV(const Rot3& rot, const Point3& t, const Velocity3& vel)
  28. : Base(Pose3(rot, t), vel) {}
  29. explicit PoseRTV(const Point3& t)
  30. : Base(Pose3(Rot3(), t),Vector3::Zero()) {}
  31. PoseRTV(const Pose3& pose, const Velocity3& vel)
  32. : Base(pose, vel) {}
  33. explicit PoseRTV(const Pose3& pose)
  34. : Base(pose,Vector3::Zero()) {}
  35. // Construct from Base
  36. PoseRTV(const Base& base)
  37. : Base(base) {}
  38. /** build from components - useful for data files */
  39. PoseRTV(double roll, double pitch, double yaw, double x, double y, double z,
  40. double vx, double vy, double vz);
  41. /** build from single vector - useful for Matlab - in RtV format */
  42. explicit PoseRTV(const Vector& v);
  43. // access
  44. const Pose3& pose() const { return first; }
  45. const Velocity3& v() const { return second; }
  46. const Point3& t() const { return pose().translation(); }
  47. const Rot3& R() const { return pose().rotation(); }
  48. // longer function names
  49. const Point3& translation() const { return pose().translation(); }
  50. const Rot3& rotation() const { return pose().rotation(); }
  51. const Velocity3& velocity() const { return second; }
  52. // Access to vector for ease of use with Matlab
  53. // and avoidance of Point3
  54. Vector vector() const;
  55. Vector translationVec() const { return pose().translation(); }
  56. const Velocity3& velocityVec() const { return velocity(); }
  57. // testable
  58. bool equals(const PoseRTV& other, double tol=1e-6) const;
  59. void print(const std::string& s="") const;
  60. /// @name Manifold
  61. /// @{
  62. using Base::dimension;
  63. using Base::dim;
  64. using Base::Dim;
  65. using Base::retract;
  66. using Base::localCoordinates;
  67. using Base::LocalCoordinates;
  68. /// @}
  69. /// @name measurement functions
  70. /// @{
  71. /** range between translations */
  72. double range(const PoseRTV& other,
  73. OptionalJacobian<1,9> H1=boost::none,
  74. OptionalJacobian<1,9> H2=boost::none) const;
  75. /// @}
  76. /// @name IMU-specific
  77. /// @{
  78. /// Dynamics integrator for ground robots
  79. /// Always move from time 1 to time 2
  80. PoseRTV planarDynamics(double vel_rate, double heading_rate, double max_accel, double dt) const;
  81. /// Simulates flying robot with simple flight model
  82. /// Integrates state x1 -> x2 given controls
  83. /// x1 = {p1, r1, v1}, x2 = {p2, r2, v2}, all in global coordinates
  84. /// @return x2
  85. PoseRTV flyingDynamics(double pitch_rate, double heading_rate, double lift_control, double dt) const;
  86. /// General Dynamics update - supply control inputs in body frame
  87. PoseRTV generalDynamics(const Vector& accel, const Vector& gyro, double dt) const;
  88. /// Dynamics predictor for both ground and flying robots, given states at 1 and 2
  89. /// Always move from time 1 to time 2
  90. /// @return imu measurement, as [accel, gyro]
  91. Vector6 imuPrediction(const PoseRTV& x2, double dt) const;
  92. /// predict measurement and where Point3 for x2 should be, as a way
  93. /// of enforcing a velocity constraint
  94. /// This version splits out the rotation and velocity for x2
  95. Point3 translationIntegration(const Rot3& r2, const Velocity3& v2, double dt) const;
  96. /// predict measurement and where Point3 for x2 should be, as a way
  97. /// of enforcing a velocity constraint
  98. /// This version takes a full PoseRTV, but ignores the existing translation for x2
  99. inline Point3 translationIntegration(const PoseRTV& x2, double dt) const {
  100. return translationIntegration(x2.rotation(), x2.velocity(), dt);
  101. }
  102. /// @return a vector for Matlab compatibility
  103. inline Vector translationIntegrationVec(const PoseRTV& x2, double dt) const {
  104. return translationIntegration(x2, dt);
  105. }
  106. /**
  107. * Apply transform to this pose, with optional derivatives
  108. * equivalent to:
  109. * local = trans.transformFrom(global, Dtrans, Dglobal)
  110. *
  111. * Note: the transform jacobian convention is flipped
  112. */
  113. PoseRTV transformed_from(const Pose3& trans,
  114. ChartJacobian Dglobal = boost::none,
  115. OptionalJacobian<9, 6> Dtrans = boost::none) const;
  116. /// @}
  117. /// @name Utility functions
  118. /// @{
  119. /// RRTMbn - Function computes the rotation rate transformation matrix from
  120. /// body axis rates to euler angle (global) rates
  121. static Matrix RRTMbn(const Vector3& euler);
  122. static Matrix RRTMbn(const Rot3& att);
  123. /// RRTMnb - Function computes the rotation rate transformation matrix from
  124. /// euler angle rates to body axis rates
  125. static Matrix RRTMnb(const Vector3& euler);
  126. static Matrix RRTMnb(const Rot3& att);
  127. /// @}
  128. private:
  129. /** Serialization function */
  130. friend class boost::serialization::access;
  131. template<class Archive>
  132. void serialize(Archive & ar, const unsigned int /*version*/) {
  133. ar & BOOST_SERIALIZATION_NVP(first);
  134. ar & BOOST_SERIALIZATION_NVP(second);
  135. }
  136. };
  137. template<>
  138. struct traits<PoseRTV> : public internal::LieGroup<PoseRTV> {};
  139. // Define Range functor specializations that are used in RangeFactor
  140. template <typename A1, typename A2> struct Range;
  141. template<>
  142. struct Range<PoseRTV, PoseRTV> : HasRange<PoseRTV, PoseRTV, double> {};
  143. } // \namespace gtsam