control_motordetect.cpp 6.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195
  1. #include "Sub.h"
  2. #include "stdio.h"
  3. /*
  4. * control_motordetect.cpp - init and run calls for motordetect flightmode;
  5. *
  6. * This mode pulses all thrusters to detect if they need to be reversed.
  7. * This still requires that the user has the correct frame selected and the motors
  8. * are connected to the correct ESCs.
  9. *
  10. * For each motor:
  11. * wait until vehicle is stopped for > 500ms
  12. * apply throttle up for 500ms
  13. * If results are good:
  14. * save direction and try the next motor.
  15. * else
  16. * wait until vehicle is stopped for > 500ms
  17. * apply throttle down for 500ms
  18. * If results are good
  19. * save direction and try the next motor.
  20. * If results are bad
  21. * Abort!
  22. */
  23. namespace {
  24. // controller states
  25. enum test_state {
  26. STANDBY,
  27. SETTLING,
  28. THRUSTING,
  29. DETECTING,
  30. DONE
  31. };
  32. enum direction {
  33. UP = 1,
  34. DOWN = -1
  35. };
  36. static uint32_t settling_timer;
  37. static uint32_t thrusting_timer;
  38. static uint8_t md_state;
  39. static uint8_t current_motor;
  40. static int16_t current_direction;
  41. }
  42. bool Sub::motordetect_init()
  43. {
  44. current_motor = 0;
  45. md_state = STANDBY;
  46. current_direction = UP;
  47. return true;
  48. }
  49. void Sub::motordetect_run()
  50. {
  51. // if not armed set throttle to zero and exit immediately
  52. if (!motors.armed()) {
  53. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  54. // Force all motors to stop
  55. for(uint8_t i=0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
  56. if (motors.motor_is_enabled(i)) {
  57. motors.output_test_num(i, 1500);
  58. }
  59. }
  60. md_state = STANDBY;
  61. return;
  62. }
  63. switch(md_state) {
  64. // Motor detection is not running, set it up to start.
  65. case STANDBY:
  66. current_direction = UP;
  67. current_motor = 0;
  68. settling_timer = AP_HAL::millis();
  69. md_state = SETTLING;
  70. break;
  71. // Wait until sub stays for 500ms not spinning and leveled.
  72. case SETTLING:
  73. // Force all motors to stop
  74. for (uint8_t i=0; i <AP_MOTORS_MAX_NUM_MOTORS; i++) {
  75. if (motors.motor_is_enabled(i)) {
  76. !motors.output_test_num(i, 1500);
  77. }
  78. }
  79. // wait until gyro product is under a certain(experimental) threshold
  80. if ((ahrs.get_gyro()*ahrs.get_gyro()) > 0.01) {
  81. settling_timer = AP_HAL::millis();
  82. }
  83. // then wait 500ms more
  84. if (AP_HAL::millis() > (settling_timer + 500)) {
  85. md_state = THRUSTING;
  86. thrusting_timer = AP_HAL::millis();
  87. }
  88. break;
  89. // Thrusts motor for 500ms
  90. case THRUSTING:
  91. if (AP_HAL::millis() < (thrusting_timer + 500)) {
  92. if (!motors.output_test_num(current_motor, 1500 + 300*current_direction)) {
  93. md_state = DONE;
  94. };
  95. } else {
  96. md_state = DETECTING;
  97. }
  98. break;
  99. // Checks the result of thrusting the motor.
  100. // Starts again at the other direction if unable to get a good reading.
  101. // Fails if it is the second reading and it is still not good.
  102. // Set things up to test the next motor if the reading is good.
  103. case DETECTING:
  104. {
  105. // This logic results in a vector such as (1, -1, 0)
  106. // TODO: make these thresholds parameters
  107. Vector3f gyro = ahrs.get_gyro();
  108. bool roll_up = gyro.x > 0.4;
  109. bool roll_down = gyro.x < -0.4;
  110. int roll = (int(roll_up) - int(roll_down))*current_direction;
  111. bool pitch_up = gyro.y > 0.4;
  112. bool pitch_down = gyro.y < -0.4;
  113. int pitch = (int(pitch_up) - int(pitch_down))*current_direction;
  114. bool yaw_up = gyro.z > 0.5;
  115. bool yaw_down = gyro.z < -0.5;
  116. int yaw = (+int(yaw_up) - int(yaw_down))*current_direction;
  117. // Readings from the motors table
  118. Vector3f motor_directions = motors.get_motor_angular_factors(current_motor);
  119. // Readings we got from the tests
  120. Vector3f read_directions = Vector3f(roll, pitch, yaw);
  121. // Any correct reading counts, any inverted one invalidates the test
  122. int correct_readings = 0;
  123. int inverted_readings = 0;
  124. for (int i=0; i<3; i++) {
  125. // Factor read as 0 does not count
  126. if (fabsf(read_directions[i]) < 0.1f || fabsf(motor_directions[i]) < 0.1f ) {
  127. continue;
  128. } // Correct reading
  129. else if (fabsf(motor_directions[i] - read_directions[i]) < 0.1f) {
  130. correct_readings += 1;
  131. } // Inverted reading
  132. else if (fabsf(motor_directions[i] + read_directions[i]) < 0.1f) {
  133. inverted_readings += 1;
  134. }
  135. }
  136. // Detected the motor at the correct direction
  137. if (correct_readings > 0 && inverted_readings == 0) {
  138. gcs().send_text(MAV_SEVERITY_INFO, "Thruster %d is ok! Saving it!", current_motor + 1);
  139. motors.set_reversed(current_motor, false);
  140. }
  141. // Motor detected and inverted
  142. else if (inverted_readings > 0 && correct_readings == 0) {
  143. gcs().send_text(MAV_SEVERITY_INFO, "Thruster %d is reversed! Saving it!", current_motor + 1);
  144. motors.set_reversed(current_motor, true);
  145. }
  146. // Could not detect motor properly
  147. else {
  148. gcs().send_text(MAV_SEVERITY_INFO, "Bad thrust read, trying to push the other way...");
  149. // If we got here, we couldn't identify anything that made sense.
  150. // Let's try pushing the thruster the other way, maybe we are in too shallow waters or hit something
  151. if (current_direction == DOWN) {
  152. // The reading for the second direction was also bad, we failed.
  153. gcs().send_text(MAV_SEVERITY_WARNING, "Failed! Please check Thruster %d and frame setup!", current_motor + 1);
  154. md_state = DONE;
  155. break;
  156. }
  157. current_direction = DOWN;
  158. md_state = SETTLING;
  159. break;
  160. }
  161. // If we got here, we have a decent motor reading
  162. md_state = SETTLING;
  163. // Test the next motor, if it exists
  164. current_motor++;
  165. current_direction = UP;
  166. if (!motors.motor_is_enabled(current_motor)) {
  167. md_state = DONE;
  168. gcs().send_text(MAV_SEVERITY_WARNING, "Motor direction detection is complete.");
  169. }
  170. break;
  171. }
  172. case DONE:
  173. control_mode = prev_control_mode;
  174. arming.disarm();
  175. break;
  176. }
  177. }