Compass_PerMotor.cpp 6.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231
  1. /*
  2. per-motor compass compensation
  3. */
  4. #include "AP_Compass.h"
  5. #include <GCS_MAVLink/GCS.h>
  6. #include <SRV_Channel/SRV_Channel.h>
  7. extern const AP_HAL::HAL &hal;
  8. const AP_Param::GroupInfo Compass_PerMotor::var_info[] = {
  9. // @Param: _EN
  10. // @DisplayName: per-motor compass correction enable
  11. // @Description: This enables per-motor compass corrections
  12. // @Values: 0:Disabled,1:Enabled
  13. // @User: Advanced
  14. AP_GROUPINFO_FLAGS("_EN", 1, Compass_PerMotor, enable, 0, AP_PARAM_FLAG_ENABLE),
  15. // @Param: _EXP
  16. // @DisplayName: per-motor exponential correction
  17. // @Description: This is the exponential correction for the power output of the motor for per-motor compass correction
  18. // @Range: 0 2
  19. // @Increment: 0.01
  20. // @User: Advanced
  21. AP_GROUPINFO("_EXP", 2, Compass_PerMotor, expo, 0.65),
  22. // @Param: 1_X
  23. // @DisplayName: Compass per-motor1 X
  24. // @Description: Compensation for X axis of motor1
  25. // @User: Advanced
  26. // @Param: 1_Y
  27. // @DisplayName: Compass per-motor1 Y
  28. // @Description: Compensation for Y axis of motor1
  29. // @User: Advanced
  30. // @Param: 1_Z
  31. // @DisplayName: Compass per-motor1 Z
  32. // @Description: Compensation for Z axis of motor1
  33. // @User: Advanced
  34. AP_GROUPINFO("1", 3, Compass_PerMotor, compensation[0], 0),
  35. // @Param: 2_X
  36. // @DisplayName: Compass per-motor2 X
  37. // @Description: Compensation for X axis of motor2
  38. // @User: Advanced
  39. // @Param: 2_Y
  40. // @DisplayName: Compass per-motor2 Y
  41. // @Description: Compensation for Y axis of motor2
  42. // @User: Advanced
  43. // @Param: 2_Z
  44. // @DisplayName: Compass per-motor2 Z
  45. // @Description: Compensation for Z axis of motor2
  46. // @User: Advanced
  47. AP_GROUPINFO("2", 4, Compass_PerMotor, compensation[1], 0),
  48. // @Param: 3_X
  49. // @DisplayName: Compass per-motor3 X
  50. // @Description: Compensation for X axis of motor3
  51. // @User: Advanced
  52. // @Param: 3_Y
  53. // @DisplayName: Compass per-motor3 Y
  54. // @Description: Compensation for Y axis of motor3
  55. // @User: Advanced
  56. // @Param: 3_Z
  57. // @DisplayName: Compass per-motor3 Z
  58. // @Description: Compensation for Z axis of motor3
  59. // @User: Advanced
  60. AP_GROUPINFO("3", 5, Compass_PerMotor, compensation[2], 0),
  61. // @Param: 4_X
  62. // @DisplayName: Compass per-motor4 X
  63. // @Description: Compensation for X axis of motor4
  64. // @User: Advanced
  65. // @Param: 4_Y
  66. // @DisplayName: Compass per-motor4 Y
  67. // @Description: Compensation for Y axis of motor4
  68. // @User: Advanced
  69. // @Param: 4_Z
  70. // @DisplayName: Compass per-motor4 Z
  71. // @Description: Compensation for Z axis of motor4
  72. // @User: Advanced
  73. AP_GROUPINFO("4", 6, Compass_PerMotor, compensation[3], 0),
  74. AP_GROUPEND
  75. };
  76. // constructor
  77. Compass_PerMotor::Compass_PerMotor(Compass &_compass) :
  78. compass(_compass)
  79. {
  80. AP_Param::setup_object_defaults(this, var_info);
  81. }
  82. // return current scaled motor output
  83. float Compass_PerMotor::scaled_output(uint8_t motor)
  84. {
  85. if (!have_motor_map) {
  86. if (SRV_Channels::find_channel(SRV_Channel::k_motor1, motor_map[0]) &&
  87. SRV_Channels::find_channel(SRV_Channel::k_motor2, motor_map[1]) &&
  88. SRV_Channels::find_channel(SRV_Channel::k_motor3, motor_map[2]) &&
  89. SRV_Channels::find_channel(SRV_Channel::k_motor4, motor_map[3])) {
  90. have_motor_map = true;
  91. }
  92. }
  93. if (!have_motor_map) {
  94. return 0;
  95. }
  96. // this currently assumes first 4 channels.
  97. uint16_t pwm = hal.rcout->read_last_sent(motor_map[motor]);
  98. // get 0 to 1 motor demand
  99. float output = (hal.rcout->scale_esc_to_unity(pwm)+1) * 0.5f;
  100. if (output <= 0) {
  101. return 0;
  102. }
  103. // scale for voltage
  104. output *= voltage;
  105. // apply expo correction
  106. output = powf(output, expo);
  107. return output;
  108. }
  109. // per-motor calibration update
  110. void Compass_PerMotor::calibration_start(void)
  111. {
  112. for (uint8_t i=0; i<4; i++) {
  113. field_sum[i].zero();
  114. output_sum[i] = 0;
  115. count[i] = 0;
  116. start_ms[i] = 0;
  117. }
  118. // we need to ensure we get current data by throwing away several
  119. // samples. The offsets may have just changed from an offset
  120. // calibration
  121. for (uint8_t i=0; i<4; i++) {
  122. compass.read();
  123. hal.scheduler->delay(50);
  124. }
  125. base_field = compass.get_field(0);
  126. running = true;
  127. }
  128. // per-motor calibration update
  129. void Compass_PerMotor::calibration_update(void)
  130. {
  131. uint32_t now = AP_HAL::millis();
  132. // accumulate per-motor sums
  133. for (uint8_t i=0; i<4; i++) {
  134. float output = scaled_output(i);
  135. if (output <= 0) {
  136. // motor is off
  137. start_ms[i] = 0;
  138. continue;
  139. }
  140. if (start_ms[i] == 0) {
  141. start_ms[i] = now;
  142. }
  143. if (now - start_ms[i] < 500) {
  144. // motor must run for 0.5s to settle
  145. continue;
  146. }
  147. // accumulate a sample
  148. field_sum[i] += compass.get_field(0);
  149. output_sum[i] += output;
  150. count[i]++;
  151. }
  152. }
  153. // calculate per-motor calibration values
  154. void Compass_PerMotor::calibration_end(void)
  155. {
  156. for (uint8_t i=0; i<4; i++) {
  157. if (count[i] == 0) {
  158. continue;
  159. }
  160. // calculate effective output
  161. float output = output_sum[i] / count[i];
  162. // calculate amount that field changed from base field
  163. Vector3f field_change = base_field - (field_sum[i] / count[i]);
  164. if (output <= 0) {
  165. continue;
  166. }
  167. Vector3f c = field_change / output;
  168. compensation[i].set_and_save(c);
  169. }
  170. // enable per-motor compensation
  171. enable.set_and_save(1);
  172. running = false;
  173. }
  174. /*
  175. calculate total offset for per-motor compensation
  176. */
  177. void Compass_PerMotor::compensate(Vector3f &offset)
  178. {
  179. offset.zero();
  180. if (running) {
  181. // don't compensate while calibrating
  182. return;
  183. }
  184. for (uint8_t i=0; i<4; i++) {
  185. float output = scaled_output(i);
  186. const Vector3f &c = compensation[i].get();
  187. offset += c * output;
  188. }
  189. }