SIM_Calibration.cpp 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177
  1. /*
  2. * Copyright (C) 2015-2016 Intel Corporation. All rights reserved.
  3. *
  4. * This file is free software: you can redistribute it and/or modify it
  5. * under the terms of the GNU General Public License as published by the
  6. * Free Software Foundation, either version 3 of the License, or
  7. * (at your option) any later version.
  8. *
  9. * This file is distributed in the hope that it will be useful, but
  10. * WITHOUT ANY WARRANTY; without even the implied warranty of
  11. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  12. * See the GNU General Public License for more details.
  13. *
  14. * You should have received a copy of the GNU General Public License along
  15. * with this program. If not, see <http://www.gnu.org/licenses/>.
  16. */
  17. #include <assert.h>
  18. #include <AP_Math/AP_Math.h>
  19. #include "SIM_Calibration.h"
  20. #define MAX_ANGULAR_SPEED (2 * M_PI)
  21. #include <stdio.h>
  22. SITL::Calibration::Calibration(const char *frame_str)
  23. : Aircraft(frame_str)
  24. {
  25. mass = 1.5f;
  26. }
  27. void SITL::Calibration::update(const struct sitl_input &input)
  28. {
  29. Vector3f rot_accel{0, 0, 0};
  30. float switcher_pwm = input.servos[4];
  31. if (switcher_pwm < 1100) {
  32. _stop_control(input, rot_accel);
  33. } else if (switcher_pwm < 1200) {
  34. _attitude_control(input, rot_accel);
  35. } else if (switcher_pwm < 1300) {
  36. _calibration_poses(rot_accel);
  37. } else {
  38. _angular_velocity_control(input, rot_accel);
  39. }
  40. accel_body(0, 0, 0);
  41. update_dynamics(rot_accel);
  42. update_position();
  43. time_advance();
  44. // update magnetic field
  45. update_mag_field_bf();
  46. }
  47. void SITL::Calibration::_stop_control(const struct sitl_input &input,
  48. Vector3f& rot_accel)
  49. {
  50. Vector3f desired_angvel{0, 0, 0};
  51. Vector3f error = desired_angvel - gyro;
  52. float dt = frame_time_us * 1.0e-6f;
  53. rot_accel = error * (1.0f / dt);
  54. /* Provide a somewhat "smooth" transition */
  55. rot_accel *= 0.002f;
  56. }
  57. void SITL::Calibration::_attitude_control(const struct sitl_input &input,
  58. Vector3f& rot_accel)
  59. {
  60. float desired_roll = -M_PI + 2 * M_PI * (input.servos[5] - 1000) / 1000.f;
  61. float desired_pitch = -M_PI + 2 * M_PI * (input.servos[6] - 1000) / 1000.f;
  62. float desired_yaw = -M_PI + 2 * M_PI * (input.servos[7] - 1000) / 1000.f;
  63. _attitude_set(desired_roll, desired_pitch, desired_yaw, rot_accel);
  64. }
  65. void SITL::Calibration::_attitude_set(float desired_roll, float desired_pitch, float desired_yaw,
  66. Vector3f& rot_accel)
  67. {
  68. float dt = frame_time_us * 1.0e-6f;
  69. Quaternion desired_q;
  70. desired_q.from_euler(desired_roll, desired_pitch, desired_yaw);
  71. desired_q.normalize();
  72. Quaternion current_q;
  73. current_q.from_rotation_matrix(dcm);
  74. current_q.normalize();
  75. Quaternion error_q = desired_q / current_q;
  76. Vector3f angle_differential;
  77. error_q.normalize();
  78. error_q.to_axis_angle(angle_differential);
  79. Vector3f desired_angvel = angle_differential * (1 / dt);
  80. /* Provide a somewhat "smooth" transition */
  81. desired_angvel *= .005f;
  82. Vector3f error = desired_angvel - gyro;
  83. rot_accel = error * (1.0f / dt);
  84. }
  85. void SITL::Calibration::_angular_velocity_control(const struct sitl_input &in,
  86. Vector3f& rot_accel)
  87. {
  88. Vector3f axis{(float)(in.servos[5] - 1500),
  89. (float)(in.servos[6] - 1500),
  90. (float)(in.servos[7] - 1500)};
  91. float theta = MAX_ANGULAR_SPEED * (in.servos[4] - 1300) / 700.f;
  92. float dt = frame_time_us * 1.0e-6f;
  93. if (axis.length() > 0) {
  94. axis.normalize();
  95. }
  96. Vector3f desired_angvel = axis * theta;
  97. Vector3f error = desired_angvel - gyro;
  98. rot_accel = error * (1.0f / dt);
  99. /* Provide a somewhat "smooth" transition */
  100. rot_accel *= .05f;
  101. }
  102. /*
  103. move continuously through 6 calibration poses, doing a rotation
  104. about each pose over 3 seconds
  105. */
  106. void SITL::Calibration::_calibration_poses(Vector3f& rot_accel)
  107. {
  108. const struct pose {
  109. int16_t roll, pitch, yaw;
  110. uint8_t axis;
  111. } poses[] = {
  112. { 0, 0, 0, 0 },
  113. { 0, 0, 0, 1 },
  114. { 0, 0, 0, 2 },
  115. { 90, 0, 0, 1 },
  116. { 0, 90, 0, 1 },
  117. { 0, 180, 0, 2 },
  118. { 45, 0, 0, 1 },
  119. { 0, 45, 0, 2 },
  120. { 0, 0, 45, 0 },
  121. { 30, 0, 0, 1 },
  122. { 0, 30, 0, 0 },
  123. { 30, 0, 0, 1 },
  124. { 0, 0, 30, 0 },
  125. { 0, 0, 30, 1 },
  126. { 60, 20, 0, 1 },
  127. { 0, 50, 10, 0 },
  128. { 0, 30, 50, 1 },
  129. { 0, 30, 50, 2 },
  130. };
  131. const float secs_per_pose = 6;
  132. const float rate = radians(360 / secs_per_pose);
  133. float tnow = AP_HAL::millis() * 1.0e-3;
  134. float t_in_pose = fmod(tnow, secs_per_pose);
  135. uint8_t pose_num = ((unsigned)(tnow / secs_per_pose)) % ARRAY_SIZE(poses);
  136. const struct pose &pose = poses[pose_num];
  137. // let the sensor smoothing create sensible gyro values
  138. use_smoothing = true;
  139. dcm.identity();
  140. dcm.from_euler(radians(pose.roll), radians(pose.pitch), radians(pose.yaw));
  141. Vector3f axis;
  142. axis[pose.axis] = 1;
  143. float rot_angle = rate * t_in_pose;
  144. Matrix3f r2;
  145. r2.from_axis_angle(axis, rot_angle);
  146. dcm = r2 * dcm;
  147. accel_body(0, 0, -GRAVITY_MSS);
  148. accel_body = dcm.transposed() * accel_body;
  149. }