motors.cpp 6.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180
  1. #include "Sub.h"
  2. // enable_motor_output() - enable and output lowest possible value to motors
  3. void Sub::enable_motor_output()
  4. {
  5. motors.output_min();
  6. }
  7. // motors_output - send output to motors library which will adjust and send to ESCs and servos
  8. void Sub::motors_output()
  9. {
  10. // Motor detection mode controls the thrusters directly
  11. if (control_mode == MOTOR_DETECT){
  12. return;
  13. }
  14. // check if we are performing the motor test
  15. if (ap.motor_test) {
  16. verify_motor_test();
  17. } else {
  18. motors.set_interlock(true);
  19. motors.output();
  20. }
  21. }
  22. // Initialize new style motor test
  23. // Perform checks to see if it is ok to begin the motor test
  24. // Returns true if motor test has begun
  25. bool Sub::init_motor_test()
  26. {
  27. uint32_t tnow = AP_HAL::millis();
  28. // Ten second cooldown period required with no do_set_motor requests required
  29. // after failure.
  30. if (tnow < last_do_motor_test_fail_ms + 10000 && last_do_motor_test_fail_ms > 0) {
  31. gcs().send_text(MAV_SEVERITY_CRITICAL, "10 second cooldown required after motor test");
  32. return false;
  33. }
  34. // check if safety switch has been pushed
  35. if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
  36. gcs().send_text(MAV_SEVERITY_CRITICAL,"Disarm hardware safety switch before testing motors.");
  37. return false;
  38. }
  39. // Make sure we are on the ground
  40. if (!motors.armed()) {
  41. gcs().send_text(MAV_SEVERITY_WARNING, "Arm motors before testing motors.");
  42. return false;
  43. }
  44. enable_motor_output(); // set all motor outputs to zero
  45. ap.motor_test = true;
  46. return true;
  47. }
  48. // Verify new style motor test
  49. // The motor test will fail if the interval between received
  50. // MAV_CMD_DO_SET_MOTOR requests exceeds a timeout period
  51. // Returns true if it is ok to proceed with new style motor test
  52. bool Sub::verify_motor_test()
  53. {
  54. bool pass = true;
  55. // Require at least 2 Hz incoming do_set_motor requests
  56. if (AP_HAL::millis() > last_do_motor_test_ms + 500) {
  57. gcs().send_text(MAV_SEVERITY_INFO, "Motor test timed out!");
  58. pass = false;
  59. }
  60. if (!pass) {
  61. ap.motor_test = false;
  62. arming.disarm(); // disarm motors
  63. last_do_motor_test_fail_ms = AP_HAL::millis();
  64. return false;
  65. }
  66. return true;
  67. }
  68. bool Sub::handle_do_motor_test(mavlink_command_long_t command) {
  69. last_do_motor_test_ms = AP_HAL::millis();
  70. // If we are not already testing motors, initialize test
  71. static uint32_t tLastInitializationFailed = 0;
  72. if(!ap.motor_test) {
  73. // Do not allow initializations attempt under 2 seconds
  74. // If one fails, we need to give the user time to fix the issue
  75. // instead of spamming error messages
  76. if (AP_HAL::millis() > (tLastInitializationFailed + 2000)) {
  77. if (!init_motor_test()) {
  78. gcs().send_text(MAV_SEVERITY_WARNING, "motor test initialization failed!");
  79. tLastInitializationFailed = AP_HAL::millis();
  80. return false; // init fail
  81. }
  82. } else {
  83. return false;
  84. }
  85. }
  86. float motor_number = command.param1;
  87. float throttle_type = command.param2;
  88. float throttle = command.param3;
  89. // float timeout_s = command.param4; // not used
  90. // float motor_count = command.param5; // not used
  91. float test_type = command.param6;
  92. if (!is_equal(test_type, (float)MOTOR_TEST_ORDER_BOARD)) {
  93. gcs().send_text(MAV_SEVERITY_WARNING, "bad test type %0.2f", (double)test_type);
  94. return false; // test type not supported here
  95. }
  96. if (is_equal(throttle_type, (float)MOTOR_TEST_THROTTLE_PILOT)) {
  97. gcs().send_text(MAV_SEVERITY_WARNING, "bad throttle type %0.2f", (double)throttle_type);
  98. return false; // throttle type not supported here
  99. }
  100. if (is_equal(throttle_type, (float)MOTOR_TEST_THROTTLE_PWM)) {
  101. return motors.output_test_num(motor_number, throttle); // true if motor output is set
  102. }
  103. if (is_equal(throttle_type, (float)MOTOR_TEST_THROTTLE_PERCENT)) {
  104. throttle = constrain_float(throttle, 0.0f, 100.0f);
  105. throttle = channel_throttle->get_radio_min() + throttle / 100.0f * (channel_throttle->get_radio_max() - channel_throttle->get_radio_min());
  106. return motors.output_test_num(motor_number, throttle); // true if motor output is set
  107. }
  108. return false;
  109. }
  110. // translate wpnav roll/pitch outputs to lateral/forward
  111. void Sub::translate_wpnav_rp(float &lateral_out, float &forward_out)
  112. {
  113. // get roll and pitch targets in centidegrees
  114. int32_t lateral = wp_nav.get_roll();
  115. int32_t forward = -wp_nav.get_pitch(); // output is reversed
  116. // constrain target forward/lateral values
  117. // The outputs of wp_nav.get_roll and get_pitch should already be constrained to these values
  118. lateral = constrain_int16(lateral, -aparm.angle_max, aparm.angle_max);
  119. forward = constrain_int16(forward, -aparm.angle_max, aparm.angle_max);
  120. // Normalize
  121. lateral_out = (float)lateral/(float)aparm.angle_max;
  122. forward_out = (float)forward/(float)aparm.angle_max;
  123. }
  124. // translate wpnav roll/pitch outputs to lateral/forward
  125. void Sub::translate_circle_nav_rp(float &lateral_out, float &forward_out)
  126. {
  127. // get roll and pitch targets in centidegrees
  128. int32_t lateral = circle_nav.get_roll();
  129. int32_t forward = -circle_nav.get_pitch(); // output is reversed
  130. // constrain target forward/lateral values
  131. lateral = constrain_int16(lateral, -aparm.angle_max, aparm.angle_max);
  132. forward = constrain_int16(forward, -aparm.angle_max, aparm.angle_max);
  133. // Normalize
  134. lateral_out = (float)lateral/(float)aparm.angle_max;
  135. forward_out = (float)forward/(float)aparm.angle_max;
  136. }
  137. // translate pos_control roll/pitch outputs to lateral/forward
  138. void Sub::translate_pos_control_rp(float &lateral_out, float &forward_out)
  139. {
  140. // get roll and pitch targets in centidegrees
  141. int32_t lateral = pos_control.get_roll();
  142. int32_t forward = -pos_control.get_pitch(); // output is reversed
  143. // constrain target forward/lateral values
  144. lateral = constrain_int16(lateral, -aparm.angle_max, aparm.angle_max);
  145. forward = constrain_int16(forward, -aparm.angle_max, aparm.angle_max);
  146. // Normalize
  147. lateral_out = (float)lateral/(float)aparm.angle_max;
  148. forward_out = (float)forward/(float)aparm.angle_max;
  149. }