SRV_Channel_aux.cpp 28 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905
  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. SRV_Channel_aux.cpp - handling of servo auxillary functions
  15. */
  16. #include "SRV_Channel.h"
  17. #include <AP_Math/AP_Math.h>
  18. #include <AP_HAL/AP_HAL.h>
  19. #include <RC_Channel/RC_Channel.h>
  20. #include <AP_RCMapper/AP_RCMapper.h>
  21. extern const AP_HAL::HAL& hal;
  22. /// map a function to a servo channel and output it
  23. void SRV_Channel::output_ch(void)
  24. {
  25. int8_t passthrough_from = -1;
  26. // take care of special function cases
  27. switch(function)
  28. {
  29. case k_manual: // manual
  30. passthrough_from = ch_num;
  31. break;
  32. case k_rcin1 ... k_rcin16: // rc pass-thru
  33. passthrough_from = int8_t(function - k_rcin1);
  34. break;
  35. }
  36. if (passthrough_from != -1) {
  37. // we are doing passthrough from input to output for this channel
  38. RC_Channel *c = rc().channel(passthrough_from);
  39. if (c) {
  40. if (SRV_Channels::passthrough_disabled()) {
  41. output_pwm = c->get_radio_trim();
  42. } else {
  43. const int16_t radio_in = c->get_radio_in();
  44. if (!ign_small_rcin_changes) {
  45. output_pwm = radio_in;
  46. previous_radio_in = radio_in;
  47. } else {
  48. // check if rc input value has changed by more than the deadzone
  49. if (abs(radio_in - previous_radio_in) > c->get_dead_zone()) {
  50. output_pwm = radio_in;
  51. ign_small_rcin_changes = false;
  52. }
  53. }
  54. }
  55. }
  56. }
  57. if (!(SRV_Channels::disabled_mask & (1U<<ch_num))) {
  58. hal.rcout->write(ch_num, output_pwm);
  59. }
  60. }
  61. /*
  62. call output_ch() on all channels
  63. */
  64. void SRV_Channels::output_ch_all(void)
  65. {
  66. for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
  67. channels[i].output_ch();
  68. }
  69. }
  70. /*
  71. return the current function for a channel
  72. */
  73. SRV_Channel::Aux_servo_function_t SRV_Channels::channel_function(uint8_t channel)
  74. {
  75. if (channel < NUM_SERVO_CHANNELS) {
  76. return (SRV_Channel::Aux_servo_function_t)channels[channel].function.get();
  77. }
  78. return SRV_Channel::k_none;
  79. }
  80. /*
  81. setup a channels aux servo function
  82. */
  83. void SRV_Channel::aux_servo_function_setup(void)
  84. {
  85. if (type_setup) {
  86. return;
  87. }
  88. switch (function) {
  89. case k_flap:
  90. case k_flap_auto:
  91. case k_egg_drop:
  92. set_range(100);
  93. break;
  94. case k_heli_rsc:
  95. case k_heli_tail_rsc:
  96. case k_motor_tilt:
  97. case k_boost_throttle:
  98. set_range(1000);
  99. break;
  100. case k_aileron_with_input:
  101. case k_elevator_with_input:
  102. case k_aileron:
  103. case k_elevator:
  104. case k_dspoilerLeft1:
  105. case k_dspoilerLeft2:
  106. case k_dspoilerRight1:
  107. case k_dspoilerRight2:
  108. case k_rudder:
  109. case k_steering:
  110. case k_flaperon_left:
  111. case k_flaperon_right:
  112. case k_tiltMotorLeft:
  113. case k_tiltMotorRight:
  114. case k_elevon_left:
  115. case k_elevon_right:
  116. case k_vtail_left:
  117. case k_vtail_right:
  118. set_angle(4500);
  119. break;
  120. case k_throttle:
  121. case k_throttleLeft:
  122. case k_throttleRight:
  123. // fixed wing throttle
  124. set_range(100);
  125. break;
  126. default:
  127. break;
  128. }
  129. }
  130. /// setup the output range types of all functions
  131. void SRV_Channels::update_aux_servo_function(void)
  132. {
  133. if (!channels) {
  134. return;
  135. }
  136. function_mask.clearall();
  137. for (uint8_t i = 0; i < SRV_Channel::k_nr_aux_servo_functions; i++) {
  138. functions[i].channel_mask = 0;
  139. }
  140. // set auxiliary ranges
  141. for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
  142. if ((uint8_t)channels[i].function.get() < SRV_Channel::k_nr_aux_servo_functions) {
  143. channels[i].aux_servo_function_setup();
  144. function_mask.set((uint8_t)channels[i].function.get());
  145. functions[channels[i].function.get()].channel_mask |= 1U<<i;
  146. }
  147. }
  148. initialised = true;
  149. }
  150. /// Should be called after the the servo functions have been initialized
  151. void SRV_Channels::enable_aux_servos()
  152. {
  153. hal.rcout->set_default_rate(uint16_t(_singleton->default_rate.get()));
  154. update_aux_servo_function();
  155. // enable all channels that are set to a valid function. This
  156. // includes k_none servos, which allows those to get their initial
  157. // trim value on startup
  158. for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
  159. SRV_Channel &c = channels[i];
  160. // see if it is a valid function
  161. if ((uint8_t)c.function.get() < SRV_Channel::k_nr_aux_servo_functions) {
  162. hal.rcout->enable_ch(c.ch_num);
  163. }
  164. /*
  165. for channels which have been marked as digital output then the
  166. MIN/MAX/TRIM values have no meaning for controlling output, as
  167. the HAL handles the scaling. We still need to cope with places
  168. in the code that may try to set a PWM value however, so to
  169. ensure consistency we force the MIN/MAX/TRIM to be consistent
  170. across all digital channels. We use a MIN/MAX of 1000/2000, and
  171. set TRIM to either 1000 or 1500 depending on whether the channel
  172. is reversible
  173. */
  174. if (digital_mask & (1U<<i)) {
  175. c.servo_min.set(1000);
  176. c.servo_max.set(2000);
  177. if (reversible_mask & (1U<<i)) {
  178. c.servo_trim.set(1500);
  179. } else {
  180. c.servo_trim.set(1000);
  181. }
  182. }
  183. }
  184. #if HAL_SUPPORT_RCOUT_SERIAL
  185. blheli_ptr->update();
  186. #endif
  187. }
  188. /// enable output channels using a channel mask
  189. void SRV_Channels::enable_by_mask(uint16_t mask)
  190. {
  191. for (uint8_t i = 0; i < 16; i++) {
  192. if (mask & (1U<<i)) {
  193. hal.rcout->enable_ch(i);
  194. }
  195. }
  196. }
  197. /*
  198. set radio_out for all channels matching the given function type
  199. */
  200. void SRV_Channels::set_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t value)
  201. {
  202. if (!function_assigned(function)) {
  203. return;
  204. }
  205. for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
  206. if (channels[i].function.get() == function) {
  207. channels[i].set_output_pwm(value);
  208. channels[i].output_ch();
  209. }
  210. }
  211. }
  212. /*
  213. set radio_out for all channels matching the given function type
  214. trim the output assuming a 1500 center on the given value
  215. reverses pwm output based on channel reversed property
  216. */
  217. void
  218. SRV_Channels::set_output_pwm_trimmed(SRV_Channel::Aux_servo_function_t function, int16_t value)
  219. {
  220. if (!function_assigned(function)) {
  221. return;
  222. }
  223. for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
  224. if (channels[i].function.get() == function) {
  225. int16_t value2;
  226. if (channels[i].get_reversed()) {
  227. value2 = 1500 - value + channels[i].get_trim();
  228. } else {
  229. value2 = value - 1500 + channels[i].get_trim();
  230. }
  231. channels[i].set_output_pwm(constrain_int16(value2,channels[i].get_output_min(),channels[i].get_output_max()));
  232. channels[i].output_ch();
  233. }
  234. }
  235. }
  236. /*
  237. set and save the trim value to current output for all channels matching
  238. the given function type
  239. */
  240. void
  241. SRV_Channels::set_trim_to_servo_out_for(SRV_Channel::Aux_servo_function_t function)
  242. {
  243. if (!function_assigned(function)) {
  244. return;
  245. }
  246. for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
  247. if (channels[i].function.get() == function) {
  248. channels[i].servo_trim.set_and_save_ifchanged(channels[i].output_pwm);
  249. }
  250. }
  251. }
  252. /*
  253. copy radio_in to radio_out for a given function
  254. */
  255. void
  256. SRV_Channels::copy_radio_in_out(SRV_Channel::Aux_servo_function_t function, bool do_input_output)
  257. {
  258. if (!function_assigned(function)) {
  259. return;
  260. }
  261. for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
  262. if (channels[i].function.get() == function) {
  263. RC_Channel *c = rc().channel(channels[i].ch_num);
  264. if (c == nullptr) {
  265. continue;
  266. }
  267. channels[i].set_output_pwm(c->get_radio_in());
  268. if (do_input_output) {
  269. channels[i].output_ch();
  270. }
  271. }
  272. }
  273. }
  274. /*
  275. copy radio_in to radio_out for a channel mask
  276. */
  277. void
  278. SRV_Channels::copy_radio_in_out_mask(uint16_t mask)
  279. {
  280. for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
  281. if ((1U<<i) & mask) {
  282. RC_Channel *c = rc().channel(channels[i].ch_num);
  283. if (c == nullptr) {
  284. continue;
  285. }
  286. channels[i].set_output_pwm(c->get_radio_in());
  287. }
  288. }
  289. }
  290. /*
  291. setup failsafe value for an auxiliary function type to a LimitValue
  292. */
  293. void
  294. SRV_Channels::set_failsafe_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t pwm)
  295. {
  296. if (!function_assigned(function)) {
  297. return;
  298. }
  299. for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
  300. const SRV_Channel &c = channels[i];
  301. if (c.function.get() == function) {
  302. hal.rcout->set_failsafe_pwm(1U<<c.ch_num, pwm);
  303. }
  304. }
  305. }
  306. /*
  307. setup failsafe value for an auxiliary function type to a LimitValue
  308. */
  309. void
  310. SRV_Channels::set_failsafe_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
  311. {
  312. if (!function_assigned(function)) {
  313. return;
  314. }
  315. for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
  316. const SRV_Channel &c = channels[i];
  317. if (c.function.get() == function) {
  318. uint16_t pwm = c.get_limit_pwm(limit);
  319. hal.rcout->set_failsafe_pwm(1U<<c.ch_num, pwm);
  320. }
  321. }
  322. }
  323. /*
  324. setup safety value for an auxiliary function type to a LimitValue
  325. */
  326. void
  327. SRV_Channels::set_safety_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
  328. {
  329. if (!function_assigned(function)) {
  330. return;
  331. }
  332. for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
  333. const SRV_Channel &c = channels[i];
  334. if (c.function.get() == function) {
  335. uint16_t pwm = c.get_limit_pwm(limit);
  336. hal.rcout->set_safety_pwm(1U<<c.ch_num, pwm);
  337. }
  338. }
  339. }
  340. /*
  341. set radio output value for an auxiliary function type to a LimitValue
  342. */
  343. void
  344. SRV_Channels::set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
  345. {
  346. if (!function_assigned(function)) {
  347. return;
  348. }
  349. for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
  350. SRV_Channel &c = channels[i];
  351. if (c.function.get() == function) {
  352. uint16_t pwm = c.get_limit_pwm(limit);
  353. c.set_output_pwm(pwm);
  354. if (c.function.get() == SRV_Channel::k_manual) {
  355. RC_Channel *cin = rc().channel(c.ch_num);
  356. if (cin != nullptr) {
  357. // in order for output_ch() to work for k_manual we
  358. // also have to override radio_in
  359. cin->set_radio_in(pwm);
  360. }
  361. }
  362. }
  363. }
  364. }
  365. /*
  366. return true if a particular function is assigned to at least one RC channel
  367. */
  368. bool
  369. SRV_Channels::function_assigned(SRV_Channel::Aux_servo_function_t function)
  370. {
  371. return function_mask.get(uint16_t(function));
  372. }
  373. /*
  374. set servo_out and angle_min/max, then calc_pwm and output a
  375. value. This is used to move a AP_Mount servo
  376. */
  377. void
  378. SRV_Channels::move_servo(SRV_Channel::Aux_servo_function_t function,
  379. int16_t value, int16_t angle_min, int16_t angle_max)
  380. {
  381. if (!function_assigned(function)) {
  382. return;
  383. }
  384. if (angle_max <= angle_min) {
  385. return;
  386. }
  387. float v = float(value - angle_min) / float(angle_max - angle_min);
  388. v = constrain_float(v, 0.0f, 1.0f);
  389. for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
  390. SRV_Channel &c = channels[i];
  391. if (c.function.get() == function) {
  392. float v2 = c.get_reversed()? (1-v) : v;
  393. uint16_t pwm = c.servo_min + v2 * (c.servo_max - c.servo_min);
  394. c.set_output_pwm(pwm);
  395. }
  396. }
  397. }
  398. /*
  399. set the default channel an auxiliary output function should be on
  400. */
  401. bool SRV_Channels::set_aux_channel_default(SRV_Channel::Aux_servo_function_t function, uint8_t channel)
  402. {
  403. if (!initialised) {
  404. update_aux_servo_function();
  405. }
  406. if (function_assigned(function)) {
  407. // already assigned
  408. return true;
  409. }
  410. if (channels[channel].function != SRV_Channel::k_none) {
  411. if (channels[channel].function == function) {
  412. return true;
  413. }
  414. hal.console->printf("Channel %u already assigned function %u\n",
  415. (unsigned)(channel + 1),
  416. (unsigned)channels[channel].function);
  417. return false;
  418. }
  419. channels[channel].type_setup = false;
  420. channels[channel].function.set(function);
  421. channels[channel].aux_servo_function_setup();
  422. function_mask.set((uint8_t)function);
  423. functions[function].channel_mask |= 1U<<channel;
  424. return true;
  425. }
  426. // find first channel that a function is assigned to
  427. bool SRV_Channels::find_channel(SRV_Channel::Aux_servo_function_t function, uint8_t &chan)
  428. {
  429. if (!initialised) {
  430. update_aux_servo_function();
  431. }
  432. if (!function_assigned(function)) {
  433. return false;
  434. }
  435. for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
  436. if (channels[i].function == function) {
  437. chan = channels[i].ch_num;
  438. return true;
  439. }
  440. }
  441. return false;
  442. }
  443. /*
  444. get a pointer to first auxillary channel for a channel function
  445. */
  446. SRV_Channel *SRV_Channels::get_channel_for(SRV_Channel::Aux_servo_function_t function, int8_t default_chan)
  447. {
  448. uint8_t chan;
  449. if (default_chan >= 0) {
  450. set_aux_channel_default(function, default_chan);
  451. }
  452. if (!find_channel(function, chan)) {
  453. return nullptr;
  454. }
  455. return &channels[chan];
  456. }
  457. void SRV_Channels::set_output_scaled(SRV_Channel::Aux_servo_function_t function, int16_t value)
  458. {
  459. if (function < SRV_Channel::k_nr_aux_servo_functions) {
  460. functions[function].output_scaled = value;
  461. SRV_Channel::have_pwm_mask &= ~functions[function].channel_mask;
  462. }
  463. }
  464. int16_t SRV_Channels::get_output_scaled(SRV_Channel::Aux_servo_function_t function)
  465. {
  466. if (function < SRV_Channel::k_nr_aux_servo_functions) {
  467. return functions[function].output_scaled;
  468. }
  469. return 0;
  470. }
  471. /*
  472. get mask of output channels for a function
  473. */
  474. uint16_t SRV_Channels::get_output_channel_mask(SRV_Channel::Aux_servo_function_t function)
  475. {
  476. if (!initialised) {
  477. update_aux_servo_function();
  478. }
  479. if (function < SRV_Channel::k_nr_aux_servo_functions) {
  480. return functions[function].channel_mask;
  481. }
  482. return 0;
  483. }
  484. // set the trim for a function channel to given pwm
  485. void SRV_Channels::set_trim_to_pwm_for(SRV_Channel::Aux_servo_function_t function, int16_t pwm)
  486. {
  487. for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
  488. if (channels[i].function == function) {
  489. channels[i].servo_trim.set(pwm);
  490. }
  491. }
  492. }
  493. // set the trim for a function channel to min output
  494. void SRV_Channels::set_trim_to_min_for(SRV_Channel::Aux_servo_function_t function)
  495. {
  496. for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
  497. if (channels[i].function == function) {
  498. channels[i].servo_trim.set(channels[i].get_reversed()?channels[i].servo_max:channels[i].servo_min);
  499. }
  500. }
  501. }
  502. /*
  503. set the default function for a channel
  504. */
  505. void SRV_Channels::set_default_function(uint8_t chan, SRV_Channel::Aux_servo_function_t function)
  506. {
  507. if (chan < NUM_SERVO_CHANNELS) {
  508. int8_t old = channels[chan].function;
  509. channels[chan].function.set_default((uint8_t)function);
  510. if (old != channels[chan].function && channels[chan].function == function) {
  511. function_mask.set((uint8_t)function);
  512. }
  513. }
  514. }
  515. void SRV_Channels::set_esc_scaling_for(SRV_Channel::Aux_servo_function_t function)
  516. {
  517. uint8_t chan;
  518. if (find_channel(function, chan)) {
  519. hal.rcout->set_esc_scaling(channels[chan].get_output_min(), channels[chan].get_output_max());
  520. }
  521. }
  522. /*
  523. auto-adjust channel trim from an integrator value. Positive v means
  524. adjust trim up. Negative means decrease
  525. */
  526. void SRV_Channels::adjust_trim(SRV_Channel::Aux_servo_function_t function, float v)
  527. {
  528. if (is_zero(v)) {
  529. return;
  530. }
  531. for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
  532. SRV_Channel &c = channels[i];
  533. if (function != (SRV_Channel::Aux_servo_function_t)(c.function.get())) {
  534. continue;
  535. }
  536. float change = c.reversed?-v:v;
  537. uint16_t new_trim = c.servo_trim;
  538. float trim_scaled = float(c.servo_trim - c.servo_min) / (c.servo_max - c.servo_min);
  539. if (change > 0 && trim_scaled < 0.6f) {
  540. new_trim++;
  541. } else if (change < 0 && trim_scaled > 0.4f) {
  542. new_trim--;
  543. } else {
  544. return;
  545. }
  546. c.servo_trim.set(new_trim);
  547. trimmed_mask |= 1U<<i;
  548. }
  549. }
  550. // get pwm output for the first channel of the given function type.
  551. bool SRV_Channels::get_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t &value)
  552. {
  553. uint8_t chan;
  554. if (!find_channel(function, chan)) {
  555. return false;
  556. }
  557. channels[chan].calc_pwm(functions[function].output_scaled);
  558. value = channels[chan].output_pwm;
  559. return true;
  560. }
  561. // set output pwm to trim for the given function
  562. void SRV_Channels::set_output_to_trim(SRV_Channel::Aux_servo_function_t function)
  563. {
  564. for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
  565. if (channels[i].function == function) {
  566. channels[i].set_output_pwm(channels[i].servo_trim);
  567. }
  568. }
  569. }
  570. // set output pwm to for first matching channel
  571. void SRV_Channels::set_output_pwm_first(SRV_Channel::Aux_servo_function_t function, uint16_t pwm)
  572. {
  573. for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
  574. if (channels[i].function == function) {
  575. channels[i].set_output_pwm(pwm);
  576. break;
  577. }
  578. }
  579. }
  580. /*
  581. get the normalised output for a channel function from the pwm value
  582. of the first matching channel
  583. */
  584. float SRV_Channels::get_output_norm(SRV_Channel::Aux_servo_function_t function)
  585. {
  586. uint8_t chan;
  587. if (!find_channel(function, chan)) {
  588. return 0;
  589. }
  590. channels[chan].calc_pwm(functions[function].output_scaled);
  591. return channels[chan].get_output_norm();
  592. }
  593. /*
  594. limit slew rate for an output function to given rate in percent per
  595. second. This assumes output has not yet done to the hal
  596. */
  597. void SRV_Channels::limit_slew_rate(SRV_Channel::Aux_servo_function_t function, float slew_rate, float dt)
  598. {
  599. if (slew_rate <= 0) {
  600. // nothing to do
  601. return;
  602. }
  603. for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
  604. SRV_Channel &c = channels[i];
  605. if (c.function == function) {
  606. c.calc_pwm(functions[function].output_scaled);
  607. uint16_t last_pwm = hal.rcout->read_last_sent(c.ch_num);
  608. if (last_pwm == c.output_pwm) {
  609. continue;
  610. }
  611. uint16_t max_change = (c.get_output_max() - c.get_output_min()) * slew_rate * dt * 0.01f;
  612. if (max_change == 0 || dt > 1) {
  613. // always allow some change. If dt > 1 then assume we
  614. // are just starting out, and only allow a small
  615. // change for this loop
  616. max_change = 1;
  617. }
  618. c.output_pwm = constrain_int16(c.output_pwm, last_pwm-max_change, last_pwm+max_change);
  619. }
  620. }
  621. }
  622. // call set_angle() on matching channels
  623. void SRV_Channels::set_angle(SRV_Channel::Aux_servo_function_t function, uint16_t angle)
  624. {
  625. for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
  626. if (channels[i].function == function) {
  627. channels[i].set_angle(angle);
  628. }
  629. }
  630. }
  631. // call set_range() on matching channels
  632. void SRV_Channels::set_range(SRV_Channel::Aux_servo_function_t function, uint16_t range)
  633. {
  634. for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
  635. if (channels[i].function == function) {
  636. channels[i].set_range(range);
  637. }
  638. }
  639. }
  640. // set MIN parameter for a function
  641. void SRV_Channels::set_output_min_max(SRV_Channel::Aux_servo_function_t function, uint16_t min_pwm, uint16_t max_pwm)
  642. {
  643. for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
  644. if (channels[i].function == function) {
  645. channels[i].set_output_min(min_pwm);
  646. channels[i].set_output_max(max_pwm);
  647. }
  648. }
  649. }
  650. // constrain to output min/max for function
  651. void SRV_Channels::constrain_pwm(SRV_Channel::Aux_servo_function_t function)
  652. {
  653. for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
  654. SRV_Channel &c = channels[i];
  655. if (c.function == function) {
  656. c.output_pwm = constrain_int16(c.output_pwm, c.servo_min, c.servo_max);
  657. }
  658. }
  659. }
  660. /*
  661. upgrade RC* parameters into SERVO* parameters. This does the following:
  662. - copies MIN/MAX/TRIM values from old RC parameters into new RC* parameters and SERVO* parameters.
  663. - copies RCn_FUNCTION to SERVOn_FUNCTION
  664. - maps old RCn_REV to SERVOn_REVERSE and RCn_REVERSE
  665. aux_channel_mask is a bitmask of which channels were RC_Channel_aux channels
  666. Note that this code is highly dependent on the parameter indexing of
  667. the old RC_Channel and RC_Channel_aux objects.
  668. If rcmap is passed in then the vehicle code also wants functions for
  669. the first 4 output channels to be remapped
  670. We return true if an upgrade has been done. This allows the caller
  671. to make any vehicle specific upgrades that may be needed
  672. */
  673. bool SRV_Channels::upgrade_parameters(const uint8_t rc_keys[14], uint16_t aux_channel_mask, RCMapper *rcmap)
  674. {
  675. // use SERVO16_FUNCTION as a marker to say that we have run the upgrade already
  676. if (channels[15].function.configured_in_storage()) {
  677. // upgrade already done
  678. return false;
  679. }
  680. // old system had 14 RC channels
  681. for (uint8_t i=0; i<14; i++) {
  682. uint8_t k = rc_keys[i];
  683. if (k == 0) {
  684. // missing parameter. Some vehicle types didn't have all parameters
  685. continue;
  686. }
  687. SRV_Channel &srv_chan = channels[i];
  688. RC_Channel *rc_chan = rc().channel(i);
  689. enum {
  690. FLAG_NONE=0,
  691. FLAG_IS_REVERSE=1,
  692. FLAG_AUX_ONLY=2
  693. };
  694. const struct mapping {
  695. uint8_t old_index;
  696. AP_Param *new_srv_param;
  697. AP_Param *new_rc_param;
  698. enum ap_var_type type;
  699. uint8_t flags;
  700. } mapping[] = {
  701. { 0, &srv_chan.servo_min, &rc_chan->radio_min, AP_PARAM_INT16, FLAG_NONE },
  702. { 1, &srv_chan.servo_trim, &rc_chan->radio_trim, AP_PARAM_INT16, FLAG_NONE },
  703. { 2, &srv_chan.servo_max, &rc_chan->radio_max, AP_PARAM_INT16, FLAG_NONE },
  704. { 3, &srv_chan.reversed, &rc_chan->reversed, AP_PARAM_INT8, FLAG_IS_REVERSE },
  705. { 1, &srv_chan.function, nullptr, AP_PARAM_INT8, FLAG_AUX_ONLY },
  706. };
  707. bool is_aux = aux_channel_mask & (1U<<i);
  708. for (uint8_t j=0; j<ARRAY_SIZE(mapping); j++) {
  709. const struct mapping &m = mapping[j];
  710. AP_Param::ConversionInfo info;
  711. AP_Int8 v8;
  712. AP_Int16 v16;
  713. AP_Param *v = m.type == AP_PARAM_INT16?(AP_Param*)&v16:(AP_Param*)&v8;
  714. bool aux_only = (m.flags & FLAG_AUX_ONLY)!=0;
  715. if (!is_aux && aux_only) {
  716. continue;
  717. }
  718. info.old_key = k;
  719. info.type = m.type;
  720. info.new_name = nullptr;
  721. // if this was an aux channel we need to shift by 6 bits, but not for RCn_FUNCTION
  722. info.old_group_element = (is_aux && !aux_only)?(m.old_index<<6):m.old_index;
  723. if (!AP_Param::find_old_parameter(&info, v)) {
  724. // the parameter wasn't set in the old eeprom
  725. continue;
  726. }
  727. if (m.flags & FLAG_IS_REVERSE) {
  728. // special mapping from RCn_REV to RCn_REVERSED
  729. v8.set(v8.get() == -1?1:0);
  730. }
  731. if (!m.new_srv_param->configured_in_storage()) {
  732. // not configured yet in new eeprom
  733. if (m.type == AP_PARAM_INT16) {
  734. ((AP_Int16 *)m.new_srv_param)->set_and_save_ifchanged(v16.get());
  735. } else {
  736. ((AP_Int8 *)m.new_srv_param)->set_and_save_ifchanged(v8.get());
  737. }
  738. }
  739. if (m.new_rc_param && !m.new_rc_param->configured_in_storage()) {
  740. // not configured yet in new eeprom
  741. if (m.type == AP_PARAM_INT16) {
  742. ((AP_Int16 *)m.new_rc_param)->set_and_save_ifchanged(v16.get());
  743. } else {
  744. ((AP_Int8 *)m.new_rc_param)->set_and_save_ifchanged(v8.get());
  745. }
  746. }
  747. }
  748. }
  749. if (rcmap != nullptr) {
  750. // we need to make the output functions from the rcmapped inputs
  751. const int8_t func_map[4] = { channels[0].function.get(),
  752. channels[1].function.get(),
  753. channels[2].function.get(),
  754. channels[3].function.get() };
  755. const uint8_t map[4] = { rcmap->roll(), rcmap->pitch(), rcmap->throttle(), rcmap->yaw() };
  756. for (uint8_t i=0; i<4; i++) {
  757. uint8_t m = uint8_t(map[i]-1);
  758. if (m != i && m < 4) {
  759. channels[m].function.set_and_save_ifchanged(func_map[i]);
  760. }
  761. }
  762. }
  763. // mark the upgrade as having been done
  764. channels[15].function.set_and_save(channels[15].function.get());
  765. return true;
  766. }
  767. /*
  768. Upgrade servo MIN/MAX/TRIM/REVERSE parameters for a single AP_Motors
  769. RC_Channel servo from previous firmwares, setting the equivalent
  770. parameter in the new SRV_Channels object
  771. */
  772. void SRV_Channels::upgrade_motors_servo(uint8_t ap_motors_key, uint8_t ap_motors_idx, uint8_t new_channel)
  773. {
  774. SRV_Channel &srv_chan = channels[new_channel];
  775. enum {
  776. FLAG_NONE=0,
  777. FLAG_IS_REVERSE=1
  778. };
  779. const struct mapping {
  780. uint8_t old_index;
  781. AP_Param *new_srv_param;
  782. enum ap_var_type type;
  783. uint8_t flags;
  784. } mapping[] = {
  785. { 0, &srv_chan.servo_min, AP_PARAM_INT16, FLAG_NONE },
  786. { 1, &srv_chan.servo_trim, AP_PARAM_INT16, FLAG_NONE },
  787. { 2, &srv_chan.servo_max, AP_PARAM_INT16, FLAG_NONE },
  788. { 3, &srv_chan.reversed, AP_PARAM_INT8, FLAG_IS_REVERSE },
  789. };
  790. for (uint8_t j=0; j<ARRAY_SIZE(mapping); j++) {
  791. const struct mapping &m = mapping[j];
  792. AP_Param::ConversionInfo info;
  793. AP_Int8 v8;
  794. AP_Int16 v16;
  795. AP_Param *v = m.type == AP_PARAM_INT16?(AP_Param*)&v16:(AP_Param*)&v8;
  796. info.old_key = ap_motors_key;
  797. info.type = m.type;
  798. info.new_name = nullptr;
  799. info.old_group_element = ap_motors_idx | (m.old_index<<6);
  800. if (!AP_Param::find_old_parameter(&info, v)) {
  801. // the parameter wasn't set in the old eeprom
  802. continue;
  803. }
  804. if (m.flags & FLAG_IS_REVERSE) {
  805. // special mapping from RCn_REV to RCn_REVERSED
  806. v8.set(v8.get() == -1?1:0);
  807. }
  808. // we save even if there is already a value in the new eeprom,
  809. // as that may come from the equivalent RC channel, not the
  810. // old motor servo channel
  811. if (m.type == AP_PARAM_INT16) {
  812. ((AP_Int16 *)m.new_srv_param)->set_and_save_ifchanged(v16.get());
  813. } else {
  814. ((AP_Int8 *)m.new_srv_param)->set_and_save_ifchanged(v8.get());
  815. }
  816. }
  817. }
  818. // set RC output frequency on a function output
  819. void SRV_Channels::set_rc_frequency(SRV_Channel::Aux_servo_function_t function, uint16_t frequency_hz)
  820. {
  821. uint16_t mask = 0;
  822. for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
  823. SRV_Channel &c = channels[i];
  824. if (c.function == function) {
  825. mask |= (1U<<c.ch_num);
  826. }
  827. }
  828. if (mask != 0) {
  829. hal.rcout->set_freq(mask, frequency_hz);
  830. }
  831. }