SIM_Calibration.h 3.3 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889
  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. #pragma once
  18. #include "SIM_Aircraft.h"
  19. #include <AP_Math/AP_Math.h>
  20. namespace SITL {
  21. /**
  22. * Simulation model to simulate calibration of accelerometers and compasses.
  23. *
  24. * The vehicle rotation can be controlled by sending PWM values to the servos
  25. * input, denoted by PWM[i] for the i-th channel (starting by zero). All PWM
  26. * values must be in [1000, 2000], otherwise that will cause undefined
  27. * behavior.
  28. *
  29. * There are four control modes, that are set with PWM[4]:
  30. *
  31. * 1) Stop (1000 <= PWM[4] < 1100):
  32. * Stop the vehicle, i.e., stop the actuation of the other modes.
  33. *
  34. * 2) Attitude (1100 <= PWM[4] < 1200):
  35. * Rotate the vehicle to the specified attitude. The attitude is defined
  36. * with the PWM channels 5, 6 and 7 for roll, pitch and yaw angles,
  37. * respectively. The PWM value for a desired angle in radians is given by:
  38. *
  39. * pwm(theta) = 1500 + 500 * round(theta / pi)
  40. * where -pi <= theta <= pi
  41. *
  42. * 3) Simple autonomous compass calibration (1200 <= PWM[4] < 1300):
  43. * Move continuously the vehicle through six calibration poses and do a
  44. * rotation about each pose over a short period of time.
  45. *
  46. * 4) Angular Velocity (1300 <= PWM[4] <= 2000):
  47. * Rotate the vehicle at a desired angular velocity. The angular velocity is
  48. * specified by a rotation axis and an angular speed.
  49. *
  50. * The x, y and z components of the rotation axis is given, respectively, by
  51. * the PWM channels 5, 6 and 7 with an offset of 1500. The rotation axis is
  52. * normalized internally, so that PWM[5,6,7] = [1600, 1300, 0] and
  53. * PWM[5,6,7] = [1700, 1100, 0] means the same normalized rotation axis.
  54. *
  55. * The angular speed value is specified by PWM[4]. The PWM value for a
  56. * desired angular speed in radians/s is given by:
  57. *
  58. * pwm(theta) = 1300 + 700 * round(theta / (2 * pi)),
  59. * where 0 <= theta <= 2 * pi
  60. */
  61. class Calibration : public Aircraft {
  62. public:
  63. Calibration(const char *frame_str);
  64. void update(const struct sitl_input &input) override;
  65. static Aircraft *create(const char *frame_str) {
  66. return new Calibration(frame_str);
  67. }
  68. private:
  69. void _stop_control(const struct sitl_input &input, Vector3f& rot_accel);
  70. void _attitude_set(float desired_roll, float desired_pitch, float desired_yaw,
  71. Vector3f& rot_accel);
  72. void _attitude_control(const struct sitl_input &input,
  73. Vector3f& rot_accel);
  74. void _angular_velocity_control(const struct sitl_input &input,
  75. Vector3f& rot_accel);
  76. void _calibration_poses(Vector3f& rot_accel);
  77. };
  78. }