AP_MotorsTri.cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. * AP_MotorsTri.cpp - ArduCopter motors library
  15. * Code by RandyMackay. DIYDrones.com
  16. *
  17. */
  18. #include <AP_HAL/AP_HAL.h>
  19. #include <AP_Math/AP_Math.h>
  20. #include <GCS_MAVLink/GCS.h>
  21. #include "AP_MotorsTri.h"
  22. extern const AP_HAL::HAL& hal;
  23. // init
  24. void AP_MotorsTri::init(motor_frame_class frame_class, motor_frame_type frame_type)
  25. {
  26. add_motor_num(AP_MOTORS_MOT_1);
  27. add_motor_num(AP_MOTORS_MOT_2);
  28. add_motor_num(AP_MOTORS_MOT_4);
  29. // set update rate for the 3 motors (but not the servo on channel 7)
  30. set_update_rate(_speed_hz);
  31. // set the motor_enabled flag so that the ESCs can be calibrated like other frame types
  32. motor_enabled[AP_MOTORS_MOT_1] = true;
  33. motor_enabled[AP_MOTORS_MOT_2] = true;
  34. motor_enabled[AP_MOTORS_MOT_4] = true;
  35. // find the yaw servo
  36. _yaw_servo = SRV_Channels::get_channel_for(SRV_Channel::k_motor7, AP_MOTORS_CH_TRI_YAW);
  37. if (!_yaw_servo) {
  38. gcs().send_text(MAV_SEVERITY_ERROR, "MotorsTri: unable to setup yaw channel");
  39. // don't set initialised_ok
  40. return;
  41. }
  42. // allow mapping of motor7
  43. add_motor_num(AP_MOTORS_CH_TRI_YAW);
  44. // record successful initialisation if what we setup was the desired frame_class
  45. _flags.initialised_ok = (frame_class == MOTOR_FRAME_TRI);
  46. }
  47. // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
  48. void AP_MotorsTri::set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
  49. {
  50. _flags.initialised_ok = (frame_class == MOTOR_FRAME_TRI);
  51. }
  52. // set update rate to motors - a value in hertz
  53. void AP_MotorsTri::set_update_rate(uint16_t speed_hz)
  54. {
  55. // record requested speed
  56. _speed_hz = speed_hz;
  57. // set update rate for the 3 motors (but not the servo on channel 7)
  58. uint32_t mask =
  59. 1U << AP_MOTORS_MOT_1 |
  60. 1U << AP_MOTORS_MOT_2 |
  61. 1U << AP_MOTORS_MOT_4;
  62. rc_set_freq(mask, _speed_hz);
  63. }
  64. void AP_MotorsTri::output_to_motors()
  65. {
  66. switch (_spool_state) {
  67. case SpoolState::SHUT_DOWN:
  68. // sends minimum values out to the motors
  69. rc_write(AP_MOTORS_MOT_1, output_to_pwm(0));
  70. rc_write(AP_MOTORS_MOT_2, output_to_pwm(0));
  71. rc_write(AP_MOTORS_MOT_4, output_to_pwm(0));
  72. rc_write(AP_MOTORS_CH_TRI_YAW, _yaw_servo->get_trim());
  73. break;
  74. case SpoolState::GROUND_IDLE:
  75. // sends output to motors when armed but not flying
  76. set_actuator_with_slew(_actuator[1], actuator_spin_up_to_ground_idle());
  77. set_actuator_with_slew(_actuator[2], actuator_spin_up_to_ground_idle());
  78. set_actuator_with_slew(_actuator[4], actuator_spin_up_to_ground_idle());
  79. rc_write(AP_MOTORS_MOT_1, output_to_pwm(_actuator[1]));
  80. rc_write(AP_MOTORS_MOT_2, output_to_pwm(_actuator[2]));
  81. rc_write(AP_MOTORS_MOT_4, output_to_pwm(_actuator[4]));
  82. rc_write(AP_MOTORS_CH_TRI_YAW, _yaw_servo->get_trim());
  83. break;
  84. case SpoolState::SPOOLING_UP:
  85. case SpoolState::THROTTLE_UNLIMITED:
  86. case SpoolState::SPOOLING_DOWN:
  87. // set motor output based on thrust requests
  88. set_actuator_with_slew(_actuator[1], thrust_to_actuator(_thrust_right));
  89. set_actuator_with_slew(_actuator[2], thrust_to_actuator(_thrust_left));
  90. set_actuator_with_slew(_actuator[4], thrust_to_actuator(_thrust_rear));
  91. rc_write(AP_MOTORS_MOT_1, output_to_pwm(_actuator[1]));
  92. rc_write(AP_MOTORS_MOT_2, output_to_pwm(_actuator[2]));
  93. rc_write(AP_MOTORS_MOT_4, output_to_pwm(_actuator[4]));
  94. rc_write(AP_MOTORS_CH_TRI_YAW, calc_yaw_radio_output(_pivot_angle, radians(_yaw_servo_angle_max_deg)));
  95. break;
  96. }
  97. }
  98. // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
  99. // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
  100. uint16_t AP_MotorsTri::get_motor_mask()
  101. {
  102. // tri copter uses channels 1,2,4 and 7
  103. uint16_t motor_mask = (1U << AP_MOTORS_MOT_1) |
  104. (1U << AP_MOTORS_MOT_2) |
  105. (1U << AP_MOTORS_MOT_4) |
  106. (1U << AP_MOTORS_CH_TRI_YAW);
  107. uint16_t mask = rc_map_mask(motor_mask);
  108. // add parent's mask
  109. mask |= AP_MotorsMulticopter::get_motor_mask();
  110. return mask;
  111. }
  112. // output_armed - sends commands to the motors
  113. // includes new scaling stability patch
  114. void AP_MotorsTri::output_armed_stabilizing()
  115. {
  116. float roll_thrust; // roll thrust input value, +/- 1.0
  117. float pitch_thrust; // pitch thrust input value, +/- 1.0
  118. float yaw_thrust; // yaw thrust input value, +/- 1.0
  119. float throttle_thrust; // throttle thrust input value, 0.0 - 1.0
  120. float throttle_avg_max; // throttle thrust average maximum value, 0.0 - 1.0
  121. float throttle_thrust_best_rpy; // throttle providing maximum roll, pitch and yaw range without climbing
  122. float rpy_scale = 1.0f; // this is used to scale the roll, pitch and yaw to fit within the motor limits
  123. float rpy_low = 0.0f; // lowest motor value
  124. float rpy_high = 0.0f; // highest motor value
  125. float thr_adj; // the difference between the pilot's desired throttle and throttle_thrust_best_rpy
  126. // sanity check YAW_SV_ANGLE parameter value to avoid divide by zero
  127. _yaw_servo_angle_max_deg = constrain_float(_yaw_servo_angle_max_deg, AP_MOTORS_TRI_SERVO_RANGE_DEG_MIN, AP_MOTORS_TRI_SERVO_RANGE_DEG_MAX);
  128. // apply voltage and air pressure compensation
  129. const float compensation_gain = get_compensation_gain();
  130. roll_thrust = (_roll_in + _roll_in_ff) * compensation_gain;
  131. pitch_thrust = (_pitch_in + _pitch_in_ff) * compensation_gain;
  132. yaw_thrust = (_yaw_in + _yaw_in_ff) * compensation_gain * sinf(radians(_yaw_servo_angle_max_deg)); // we scale this so a thrust request of 1.0f will ask for full servo deflection at full rear throttle
  133. throttle_thrust = get_throttle() * compensation_gain;
  134. throttle_avg_max = _throttle_avg_max * compensation_gain;
  135. // calculate angle of yaw pivot
  136. _pivot_angle = safe_asin(yaw_thrust);
  137. if (fabsf(_pivot_angle) > radians(_yaw_servo_angle_max_deg)) {
  138. limit.yaw = true;
  139. _pivot_angle = constrain_float(_pivot_angle, -radians(_yaw_servo_angle_max_deg), radians(_yaw_servo_angle_max_deg));
  140. }
  141. float pivot_thrust_max = cosf(_pivot_angle);
  142. float thrust_max = 1.0f;
  143. // sanity check throttle is above zero and below current limited throttle
  144. if (throttle_thrust <= 0.0f) {
  145. throttle_thrust = 0.0f;
  146. limit.throttle_lower = true;
  147. }
  148. if (throttle_thrust >= _throttle_thrust_max) {
  149. throttle_thrust = _throttle_thrust_max;
  150. limit.throttle_upper = true;
  151. }
  152. throttle_avg_max = constrain_float(throttle_avg_max, throttle_thrust, _throttle_thrust_max);
  153. // The following mix may be offer less coupling between axis but needs testing
  154. //_thrust_right = roll_thrust * -0.5f + pitch_thrust * 1.0f;
  155. //_thrust_left = roll_thrust * 0.5f + pitch_thrust * 1.0f;
  156. //_thrust_rear = 0;
  157. _thrust_right = roll_thrust * -0.5f + pitch_thrust * 0.5f;
  158. _thrust_left = roll_thrust * 0.5f + pitch_thrust * 0.5f;
  159. _thrust_rear = pitch_thrust * -0.5f;
  160. // calculate roll and pitch for each motor
  161. // set rpy_low and rpy_high to the lowest and highest values of the motors
  162. // record lowest roll pitch command
  163. rpy_low = MIN(_thrust_right, _thrust_left);
  164. rpy_high = MAX(_thrust_right, _thrust_left);
  165. if (rpy_low > _thrust_rear) {
  166. rpy_low = _thrust_rear;
  167. }
  168. // check to see if the rear motor will reach maximum thrust before the front two motors
  169. if ((1.0f - rpy_high) > (pivot_thrust_max - _thrust_rear)) {
  170. thrust_max = pivot_thrust_max;
  171. rpy_high = _thrust_rear;
  172. }
  173. // calculate throttle that gives most possible room for yaw (range 1000 ~ 2000) which is the lower of:
  174. // 1. 0.5f - (rpy_low+rpy_high)/2.0 - this would give the maximum possible room margin above the highest motor and below the lowest
  175. // 2. the higher of:
  176. // a) the pilot's throttle input
  177. // b) the point _throttle_rpy_mix between the pilot's input throttle and hover-throttle
  178. // Situation #2 ensure we never increase the throttle above hover throttle unless the pilot has commanded this.
  179. // Situation #2b allows us to raise the throttle above what the pilot commanded but not so far that it would actually cause the copter to rise.
  180. // We will choose #1 (the best throttle for yaw control) if that means reducing throttle to the motors (i.e. we favor reducing throttle *because* it provides better yaw control)
  181. // We will choose #2 (a mix of pilot and hover throttle) only when the throttle is quite low. We favor reducing throttle instead of better yaw control because the pilot has commanded it
  182. // check everything fits
  183. throttle_thrust_best_rpy = MIN(0.5f * thrust_max - (rpy_low + rpy_high) / 2.0, throttle_avg_max);
  184. if (is_zero(rpy_low)) {
  185. rpy_scale = 1.0f;
  186. } else {
  187. rpy_scale = constrain_float(-throttle_thrust_best_rpy / rpy_low, 0.0f, 1.0f);
  188. }
  189. // calculate how close the motors can come to the desired throttle
  190. thr_adj = throttle_thrust - throttle_thrust_best_rpy;
  191. if (rpy_scale < 1.0f) {
  192. // Full range is being used by roll, pitch, and yaw.
  193. limit.roll = true;
  194. limit.pitch = true;
  195. if (thr_adj > 0.0f) {
  196. limit.throttle_upper = true;
  197. }
  198. thr_adj = 0.0f;
  199. } else {
  200. if (thr_adj < -(throttle_thrust_best_rpy + rpy_low)) {
  201. // Throttle can't be reduced to desired value
  202. thr_adj = -(throttle_thrust_best_rpy + rpy_low);
  203. } else if (thr_adj > thrust_max - (throttle_thrust_best_rpy + rpy_high)) {
  204. // Throttle can't be increased to desired value
  205. thr_adj = thrust_max - (throttle_thrust_best_rpy + rpy_high);
  206. limit.throttle_upper = true;
  207. }
  208. }
  209. // add scaled roll, pitch, constrained yaw and throttle for each motor
  210. _thrust_right = throttle_thrust_best_rpy + thr_adj + rpy_scale * _thrust_right;
  211. _thrust_left = throttle_thrust_best_rpy + thr_adj + rpy_scale * _thrust_left;
  212. _thrust_rear = throttle_thrust_best_rpy + thr_adj + rpy_scale * _thrust_rear;
  213. // scale pivot thrust to account for pivot angle
  214. // we should not need to check for divide by zero as _pivot_angle is constrained to the 5deg ~ 80 deg range
  215. _thrust_rear = _thrust_rear / cosf(_pivot_angle);
  216. // constrain all outputs to 0.0f to 1.0f
  217. // test code should be run with these lines commented out as they should not do anything
  218. _thrust_right = constrain_float(_thrust_right, 0.0f, 1.0f);
  219. _thrust_left = constrain_float(_thrust_left, 0.0f, 1.0f);
  220. _thrust_rear = constrain_float(_thrust_rear, 0.0f, 1.0f);
  221. }
  222. // output_test_seq - spin a motor at the pwm value specified
  223. // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
  224. // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
  225. void AP_MotorsTri::output_test_seq(uint8_t motor_seq, int16_t pwm)
  226. {
  227. // exit immediately if not armed
  228. if (!armed()) {
  229. return;
  230. }
  231. // output to motors and servos
  232. switch (motor_seq) {
  233. case 1:
  234. // front right motor
  235. rc_write(AP_MOTORS_MOT_1, pwm);
  236. break;
  237. case 2:
  238. // back motor
  239. rc_write(AP_MOTORS_MOT_4, pwm);
  240. break;
  241. case 3:
  242. // back servo
  243. rc_write(AP_MOTORS_CH_TRI_YAW, pwm);
  244. break;
  245. case 4:
  246. // front left motor
  247. rc_write(AP_MOTORS_MOT_2, pwm);
  248. break;
  249. default:
  250. // do nothing
  251. break;
  252. }
  253. }
  254. // calc_yaw_radio_output - calculate final radio output for yaw channel
  255. int16_t AP_MotorsTri::calc_yaw_radio_output(float yaw_input, float yaw_input_max)
  256. {
  257. int16_t ret;
  258. if (_yaw_servo->get_reversed()) {
  259. yaw_input = -yaw_input;
  260. }
  261. if (yaw_input >= 0) {
  262. ret = (_yaw_servo->get_trim() + (yaw_input / yaw_input_max * (_yaw_servo->get_output_max() - _yaw_servo->get_trim())));
  263. } else {
  264. ret = (_yaw_servo->get_trim() + (yaw_input / yaw_input_max * (_yaw_servo->get_trim() - _yaw_servo->get_output_min())));
  265. }
  266. return ret;
  267. }
  268. /*
  269. call vehicle supplied thrust compensation if set. This allows for
  270. vehicle specific thrust compensation for motor arrangements such as
  271. the forward motors tilting
  272. */
  273. void AP_MotorsTri::thrust_compensation(void)
  274. {
  275. if (_thrust_compensation_callback) {
  276. // convert 3 thrust values into an array indexed by motor number
  277. float thrust[4] { _thrust_right, _thrust_left, 0, _thrust_rear };
  278. // apply vehicle supplied compensation function
  279. _thrust_compensation_callback(thrust, 4);
  280. // extract compensated thrust values
  281. _thrust_right = thrust[0];
  282. _thrust_left = thrust[1];
  283. _thrust_rear = thrust[3];
  284. }
  285. }
  286. /*
  287. override tricopter tail servo output in output_motor_mask
  288. */
  289. void AP_MotorsTri::output_motor_mask(float thrust, uint8_t mask, float rudder_dt)
  290. {
  291. // normal multicopter output
  292. AP_MotorsMulticopter::output_motor_mask(thrust, mask, rudder_dt);
  293. // and override yaw servo
  294. rc_write(AP_MOTORS_CH_TRI_YAW, _yaw_servo->get_trim());
  295. }
  296. float AP_MotorsTri::get_roll_factor(uint8_t i)
  297. {
  298. float ret = 0.0f;
  299. switch (i) {
  300. // right motor
  301. case AP_MOTORS_MOT_1:
  302. ret = -1.0f;
  303. break;
  304. // left motor
  305. case AP_MOTORS_MOT_2:
  306. ret = 1.0f;
  307. break;
  308. }
  309. return ret;
  310. }