PoseRTV.cpp 8.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241
  1. /**
  2. * @file PoseRTV.cpp
  3. * @author Alex Cunningham
  4. */
  5. #include <gtsam_unstable/dynamics/PoseRTV.h>
  6. #include <gtsam/geometry/Pose2.h>
  7. #include <gtsam/base/Vector.h>
  8. namespace gtsam {
  9. using namespace std;
  10. static const Vector kGravity = Vector::Unit(3,2)*9.81;
  11. /* ************************************************************************* */
  12. double bound(double a, double min, double max) {
  13. if (a < min) return min;
  14. else if (a > max) return max;
  15. else return a;
  16. }
  17. /* ************************************************************************* */
  18. PoseRTV::PoseRTV(double roll, double pitch, double yaw, double x, double y,
  19. double z, double vx, double vy, double vz) :
  20. Base(Pose3(Rot3::RzRyRx(roll, pitch, yaw), Point3(x, y, z)),
  21. Velocity3(vx, vy, vz)) {
  22. }
  23. /* ************************************************************************* */
  24. PoseRTV::PoseRTV(const Vector& rtv) :
  25. Base(Pose3(Rot3::RzRyRx(rtv.head(3)), Point3(rtv.segment(3, 3))),
  26. Velocity3(rtv.tail(3))) {
  27. }
  28. /* ************************************************************************* */
  29. Vector PoseRTV::vector() const {
  30. Vector rtv(9);
  31. rtv.head(3) = rotation().xyz();
  32. rtv.segment(3,3) = translation();
  33. rtv.tail(3) = velocity();
  34. return rtv;
  35. }
  36. /* ************************************************************************* */
  37. bool PoseRTV::equals(const PoseRTV& other, double tol) const {
  38. return pose().equals(other.pose(), tol)
  39. && equal_with_abs_tol(velocity(), other.velocity(), tol);
  40. }
  41. /* ************************************************************************* */
  42. void PoseRTV::print(const string& s) const {
  43. cout << s << ":" << endl;
  44. gtsam::print((Vector)R().xyz(), " R:rpy");
  45. cout << " T" << t().transpose() << endl;
  46. gtsam::print((Vector)velocity(), " V");
  47. }
  48. /* ************************************************************************* */
  49. PoseRTV PoseRTV::planarDynamics(double vel_rate, double heading_rate,
  50. double max_accel, double dt) const {
  51. // split out initial state
  52. const Rot3& r1 = R();
  53. const Velocity3& v1 = v();
  54. // Update vehicle heading
  55. Rot3 r2 = r1.retract((Vector(3) << 0.0, 0.0, heading_rate * dt).finished());
  56. const double yaw2 = r2.ypr()(0);
  57. // Update vehicle position
  58. const double mag_v1 = v1.norm();
  59. // FIXME: this doesn't account for direction in velocity bounds
  60. double dv = bound(vel_rate - mag_v1, - (max_accel * dt), max_accel * dt);
  61. double mag_v2 = mag_v1 + dv;
  62. Velocity3 v2 = mag_v2 * Velocity3(cos(yaw2), sin(yaw2), 0.0);
  63. Point3 t2 = translationIntegration(r2, v2, dt);
  64. return PoseRTV(r2, t2, v2);
  65. }
  66. /* ************************************************************************* */
  67. PoseRTV PoseRTV::flyingDynamics(
  68. double pitch_rate, double heading_rate, double lift_control, double dt) const {
  69. // split out initial state
  70. const Rot3& r1 = R();
  71. const Velocity3& v1 = v();
  72. // Update vehicle heading (and normalise yaw)
  73. Vector rot_rates = (Vector(3) << 0.0, pitch_rate, heading_rate).finished();
  74. Rot3 r2 = r1.retract(rot_rates*dt);
  75. // Work out dynamics on platform
  76. const double thrust = 50.0;
  77. const double lift = 50.0;
  78. const double drag = 0.1;
  79. double yaw2 = r2.yaw();
  80. double pitch2 = r2.pitch();
  81. double forward_accel = -thrust * sin(pitch2); // r2, pitch (in global frame?) controls forward force
  82. double loss_lift = lift*std::abs(sin(pitch2));
  83. Rot3 yaw_correction_bn = Rot3::Yaw(yaw2);
  84. Point3 forward(forward_accel, 0.0, 0.0);
  85. Vector Acc_n =
  86. yaw_correction_bn.rotate(forward) // applies locally forward force in the global frame
  87. - drag * (Vector(3) << v1.x(), v1.y(), 0.0).finished() // drag term dependent on v1
  88. + Vector::Unit(3,2)*(loss_lift - lift_control); // falling due to lift lost from pitch
  89. // Update Vehicle Position and Velocity
  90. Velocity3 v2 = v1 + Velocity3(Acc_n * dt);
  91. Point3 t2 = translationIntegration(r2, v2, dt);
  92. return PoseRTV(r2, t2, v2);
  93. }
  94. /* ************************************************************************* */
  95. PoseRTV PoseRTV::generalDynamics(
  96. const Vector& accel, const Vector& gyro, double dt) const {
  97. // Integrate Attitude Equations
  98. Rot3 r2 = rotation().retract(gyro * dt);
  99. // Integrate Velocity Equations
  100. Velocity3 v2 = velocity() + Velocity3(dt * (r2.matrix() * accel + kGravity));
  101. // Integrate Position Equations
  102. Point3 t2 = translationIntegration(r2, v2, dt);
  103. return PoseRTV(t2, r2, v2);
  104. }
  105. /* ************************************************************************* */
  106. Vector6 PoseRTV::imuPrediction(const PoseRTV& x2, double dt) const {
  107. // split out states
  108. const Rot3 &r1 = R(), &r2 = x2.R();
  109. const Velocity3 &v1 = v(), &v2 = x2.v();
  110. Vector6 imu;
  111. // acceleration
  112. Vector3 accel = (v2-v1) / dt;
  113. imu.head<3>() = r2.transpose() * (accel - kGravity);
  114. // rotation rates
  115. // just using euler angles based on matlab code
  116. // FIXME: this is silly - we shouldn't use differences in Euler angles
  117. Matrix Enb = RRTMnb(r1);
  118. Vector3 euler1 = r1.xyz(), euler2 = r2.xyz();
  119. Vector3 dR = euler2 - euler1;
  120. // normalize yaw in difference (as per Mitch's code)
  121. dR(2) = Rot2::fromAngle(dR(2)).theta();
  122. dR /= dt;
  123. imu.tail<3>() = Enb * dR;
  124. // imu.tail(3) = r1.transpose() * dR;
  125. return imu;
  126. }
  127. /* ************************************************************************* */
  128. Point3 PoseRTV::translationIntegration(const Rot3& r2, const Velocity3& v2, double dt) const {
  129. // predict point for constraint
  130. // NOTE: uses simple Euler approach for prediction
  131. Point3 pred_t2 = t() + Point3(v2 * dt);
  132. return pred_t2;
  133. }
  134. /* ************************************************************************* */
  135. double PoseRTV::range(const PoseRTV& other,
  136. OptionalJacobian<1,9> H1, OptionalJacobian<1,9> H2) const {
  137. Matrix36 D_t1_pose, D_t2_other;
  138. const Point3 t1 = pose().translation(H1 ? &D_t1_pose : 0);
  139. const Point3 t2 = other.pose().translation(H2 ? &D_t2_other : 0);
  140. Matrix13 D_d_t1, D_d_t2;
  141. double d = distance3(t1, t2, H1 ? &D_d_t1 : 0, H2 ? &D_d_t2 : 0);
  142. if (H1) *H1 << D_d_t1 * D_t1_pose, 0,0,0;
  143. if (H2) *H2 << D_d_t2 * D_t2_other, 0,0,0;
  144. return d;
  145. }
  146. /* ************************************************************************* */
  147. PoseRTV PoseRTV::transformed_from(const Pose3& trans, ChartJacobian Dglobal,
  148. OptionalJacobian<9, 6> Dtrans) const {
  149. // Pose3 transform is just compose
  150. Matrix6 D_newpose_trans, D_newpose_pose;
  151. Pose3 newpose = trans.compose(pose(), D_newpose_trans, D_newpose_pose);
  152. // Note that we rotate the velocity
  153. Matrix3 D_newvel_R, D_newvel_v;
  154. Velocity3 newvel = trans.rotation().rotate(Point3(velocity()), D_newvel_R, D_newvel_v);
  155. if (Dglobal) {
  156. Dglobal->setZero();
  157. Dglobal->topLeftCorner<6,6>() = D_newpose_pose;
  158. Dglobal->bottomRightCorner<3,3>() = D_newvel_v;
  159. }
  160. if (Dtrans) {
  161. Dtrans->setZero();
  162. Dtrans->topLeftCorner<6,6>() = D_newpose_trans;
  163. Dtrans->bottomLeftCorner<3,3>() = D_newvel_R;
  164. }
  165. return PoseRTV(newpose, newvel);
  166. }
  167. /* ************************************************************************* */
  168. Matrix PoseRTV::RRTMbn(const Vector3& euler) {
  169. assert(euler.size() == 3);
  170. const double s1 = sin(euler.x()), c1 = cos(euler.x());
  171. const double t2 = tan(euler.y()), c2 = cos(euler.y());
  172. Matrix Ebn(3,3);
  173. Ebn << 1.0, s1 * t2, c1 * t2,
  174. 0.0, c1, -s1,
  175. 0.0, s1 / c2, c1 / c2;
  176. return Ebn;
  177. }
  178. /* ************************************************************************* */
  179. Matrix PoseRTV::RRTMbn(const Rot3& att) {
  180. return PoseRTV::RRTMbn(att.rpy());
  181. }
  182. /* ************************************************************************* */
  183. Matrix PoseRTV::RRTMnb(const Vector3& euler) {
  184. Matrix Enb(3,3);
  185. const double s1 = sin(euler.x()), c1 = cos(euler.x());
  186. const double s2 = sin(euler.y()), c2 = cos(euler.y());
  187. Enb << 1.0, 0.0, -s2,
  188. 0.0, c1, s1*c2,
  189. 0.0, -s1, c1*c2;
  190. return Enb;
  191. }
  192. /* ************************************************************************* */
  193. Matrix PoseRTV::RRTMnb(const Rot3& att) {
  194. return PoseRTV::RRTMnb(att.rpy());
  195. }
  196. /* ************************************************************************* */
  197. } // \namespace gtsam