RC_Channel.cpp 25 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885
  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. * RC_Channel.cpp - class for one RC channel input
  15. */
  16. #include <stdlib.h>
  17. #include <cmath>
  18. #include <AP_HAL/AP_HAL.h>
  19. extern const AP_HAL::HAL& hal;
  20. #include <AP_Math/AP_Math.h>
  21. #include "RC_Channel.h"
  22. #include <GCS_MAVLink/GCS.h>
  23. #include <AC_Avoidance/AC_Avoid.h>
  24. #include <AC_Sprayer/AC_Sprayer.h>
  25. #include <AP_Camera/AP_Camera.h>
  26. #include <AP_Gripper/AP_Gripper.h>
  27. #include <AP_LandingGear/AP_LandingGear.h>
  28. #include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
  29. #include <AP_Arming/AP_Arming.h>
  30. #include <AP_GPS/AP_GPS.h>
  31. #include <AC_Fence/AC_Fence.h>
  32. #define SWITCH_DEBOUNCE_TIME_MS 200
  33. const AP_Param::GroupInfo RC_Channel::var_info[] = {
  34. // @Param: MIN
  35. // @DisplayName: RC min PWM
  36. // @Description: RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
  37. // @Units: PWM
  38. // @Range: 800 2200
  39. // @Increment: 1
  40. // @User: Advanced
  41. AP_GROUPINFO("MIN", 1, RC_Channel, radio_min, 1000),
  42. // @Param: TRIM
  43. // @DisplayName: RC trim PWM
  44. // @Description: RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
  45. // @Units: PWM
  46. // @Range: 800 2200
  47. // @Increment: 1
  48. // @User: Advanced
  49. AP_GROUPINFO("TRIM", 2, RC_Channel, radio_trim, 1500),
  50. // @Param: MAX
  51. // @DisplayName: RC max PWM
  52. // @Description: RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
  53. // @Units: PWM
  54. // @Range: 800 2200
  55. // @Increment: 1
  56. // @User: Advanced
  57. AP_GROUPINFO("MAX", 3, RC_Channel, radio_max, 2000),
  58. // @Param: REVERSED
  59. // @DisplayName: RC reversed
  60. // @Description: Reverse channel input. Set to 0 for normal operation. Set to 1 to reverse this input channel.
  61. // @Values: 0:Normal,1:Reversed
  62. // @User: Advanced
  63. AP_GROUPINFO("REVERSED", 4, RC_Channel, reversed, 0),
  64. // @Param: DZ
  65. // @DisplayName: RC dead-zone
  66. // @Description: PWM dead zone in microseconds around trim or bottom
  67. // @Units: PWM
  68. // @Range: 0 200
  69. // @User: Advanced
  70. AP_GROUPINFO("DZ", 5, RC_Channel, dead_zone, 0),
  71. // @Param: OPTION
  72. // @DisplayName: RC input option
  73. // @Description: Function assigned to this RC channel
  74. // @Values{Copter}: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Proximity Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl, 46:RC Override Enable, 47:User Function 1, 48:User Function 2, 49:User Function 3, 58:Clear Waypoints, 60:ZigZag, 61:ZigZag SaveWP, 62:Compass Learn, 65:GPS Disable, 66:Relay5, 67:Relay6, 68:Stabilize, 69:PosHold, 70:AltHold, 71:FlowHold, 72:Circle, 73:Drift, 100:KillIMU1, 101:KillIMU2
  75. // @Values{Rover}: 0:Do Nothing, 4:RTL, 7:Save WP, 9:Camera Trigger, 11:Fence, 16:Auto, 19:Gripper, 24:Auto Mission Reset, 28:Relay On/Off, 30:Lost Rover Sound, 31:Motor Emergency Stop, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 40:Proximity Avoidance, 41:ArmDisarm, 42:SmartRTL, 46:RC Override Enable, 50:LearnCruise, 51:Manual, 52:Acro, 53:Steering, 54:Hold, 55:Guided, 56:Loiter, 57:Follow, 58:Clear Waypoints, 59:Simple, 62:Compass Learn, 63:Sailboat Tack, 65:GPS Disable, 66:Relay5, 67:Relay6, 74:Sailboat motoring 3pos, 100:KillIMU1, 101:KillIMU2,207:MainSail
  76. // @Values{Plane}: 0:Do Nothing, 4:ModeRTL, 9:Camera Trigger, 16:ModeAuto, 24:Auto Mission Reset, 28:Relay On/Off, 29:Landing Gear, 34:Relay2 On/Off, 30:Lost Plane Sound, 31:Motor Emergency Stop, 35:Relay3 On/Off, 36:Relay4 On/Off, 41:ArmDisarm, 43:InvertedFlight, 46:RC Override Enable, 51:ModeManual, 55:ModeGuided, 58:Clear Waypoints, 62:Compass Learn, 64:Reverse Throttle, 65:GPS Disable, 66:Relay5, 67:Relay6, 72:ModeCircle, 100:KillIMU1, 101:KillIMU2
  77. // @User: Standard
  78. AP_GROUPINFO_FRAME("OPTION", 6, RC_Channel, option, 0, AP_PARAM_FRAME_COPTER|AP_PARAM_FRAME_ROVER|AP_PARAM_FRAME_PLANE),
  79. AP_GROUPEND
  80. };
  81. // constructor
  82. RC_Channel::RC_Channel(void)
  83. {
  84. AP_Param::setup_object_defaults(this, var_info);
  85. }
  86. void
  87. RC_Channel::set_range(uint16_t high)
  88. {
  89. type_in = RC_CHANNEL_TYPE_RANGE;
  90. high_in = high;
  91. }
  92. void
  93. RC_Channel::set_angle(uint16_t angle)
  94. {
  95. type_in = RC_CHANNEL_TYPE_ANGLE;
  96. high_in = angle;
  97. }
  98. void
  99. RC_Channel::set_default_dead_zone(int16_t dzone)
  100. {
  101. dead_zone.set_default(abs(dzone));
  102. }
  103. bool
  104. RC_Channel::get_reverse(void) const
  105. {
  106. return bool(reversed.get());
  107. }
  108. // read input from hal.rcin or overrides
  109. bool
  110. RC_Channel::update(void)
  111. {
  112. if (has_override() && !rc().ignore_overrides()) {
  113. radio_in = override_value;
  114. } else if (!rc().ignore_receiver()) {
  115. radio_in = hal.rcin->read(ch_in);
  116. } else {
  117. return false;
  118. }
  119. if (type_in == RC_CHANNEL_TYPE_RANGE) {
  120. control_in = pwm_to_range();
  121. } else {
  122. //RC_CHANNEL_TYPE_ANGLE
  123. control_in = pwm_to_angle();
  124. }
  125. return true;
  126. }
  127. // recompute control values with no deadzone
  128. // When done this way the control_in value can be used as servo_out
  129. // to give the same output as input
  130. void
  131. RC_Channel::recompute_pwm_no_deadzone()
  132. {
  133. if (type_in == RC_CHANNEL_TYPE_RANGE) {
  134. control_in = pwm_to_range_dz(0);
  135. } else {
  136. //RC_CHANNEL_ANGLE
  137. control_in = pwm_to_angle_dz(0);
  138. }
  139. }
  140. /*
  141. return the center stick position expressed as a control_in value
  142. used for thr_mid in copter
  143. */
  144. int16_t RC_Channel::get_control_mid() const
  145. {
  146. if (type_in == RC_CHANNEL_TYPE_RANGE) {
  147. int16_t r_in = (radio_min.get() + radio_max.get())/2;
  148. if (reversed) {
  149. r_in = radio_max.get() - (r_in - radio_min.get());
  150. }
  151. int16_t radio_trim_low = radio_min + dead_zone;
  152. return (((int32_t)(high_in) * (int32_t)(r_in - radio_trim_low)) / (int32_t)(radio_max - radio_trim_low));
  153. } else {
  154. return 0;
  155. }
  156. }
  157. /*
  158. return an "angle in centidegrees" (normally -4500 to 4500) from
  159. the current radio_in value using the specified dead_zone
  160. */
  161. int16_t
  162. RC_Channel::pwm_to_angle_dz_trim(uint16_t _dead_zone, uint16_t _trim) const
  163. {
  164. int16_t radio_trim_high = _trim + _dead_zone;
  165. int16_t radio_trim_low = _trim - _dead_zone;
  166. int16_t reverse_mul = (reversed?-1:1);
  167. if (radio_in > radio_trim_high && radio_max != radio_trim_high) {
  168. return reverse_mul * ((int32_t)high_in * (int32_t)(radio_in - radio_trim_high)) / (int32_t)(radio_max - radio_trim_high);
  169. } else if (radio_in < radio_trim_low && radio_trim_low != radio_min) {
  170. return reverse_mul * ((int32_t)high_in * (int32_t)(radio_in - radio_trim_low)) / (int32_t)(radio_trim_low - radio_min);
  171. } else {
  172. return 0;
  173. }
  174. }
  175. /*
  176. return an "angle in centidegrees" (normally -4500 to 4500) from
  177. the current radio_in value using the specified dead_zone
  178. */
  179. int16_t
  180. RC_Channel::pwm_to_angle_dz(uint16_t _dead_zone) const
  181. {
  182. return pwm_to_angle_dz_trim(_dead_zone, radio_trim);
  183. }
  184. /*
  185. return an "angle in centidegrees" (normally -4500 to 4500) from
  186. the current radio_in value
  187. */
  188. int16_t
  189. RC_Channel::pwm_to_angle() const
  190. {
  191. return pwm_to_angle_dz(dead_zone);
  192. }
  193. /*
  194. convert a pulse width modulation value to a value in the configured
  195. range, using the specified deadzone
  196. */
  197. int16_t
  198. RC_Channel::pwm_to_range_dz(uint16_t _dead_zone) const
  199. {
  200. int16_t r_in = constrain_int16(radio_in, radio_min.get(), radio_max.get());
  201. if (reversed) {
  202. r_in = radio_max.get() - (r_in - radio_min.get());
  203. }
  204. int16_t radio_trim_low = radio_min + _dead_zone;
  205. if (r_in > radio_trim_low) {
  206. return (((int32_t)(high_in) * (int32_t)(r_in - radio_trim_low)) / (int32_t)(radio_max - radio_trim_low));
  207. }
  208. return 0;
  209. }
  210. /*
  211. convert a pulse width modulation value to a value in the configured
  212. range
  213. */
  214. int16_t
  215. RC_Channel::pwm_to_range() const
  216. {
  217. return pwm_to_range_dz(dead_zone);
  218. }
  219. int16_t RC_Channel::get_control_in_zero_dz(void) const
  220. {
  221. if (type_in == RC_CHANNEL_TYPE_RANGE) {
  222. return pwm_to_range_dz(0);
  223. }
  224. return pwm_to_angle_dz(0);
  225. }
  226. // ------------------------------------------
  227. float
  228. RC_Channel::norm_input() const
  229. {
  230. float ret;
  231. int16_t reverse_mul = (reversed?-1:1);
  232. if (radio_in < radio_trim) {
  233. if (radio_min >= radio_trim) {
  234. return 0.0f;
  235. }
  236. ret = reverse_mul * (float)(radio_in - radio_trim) / (float)(radio_trim - radio_min);
  237. } else {
  238. if (radio_max <= radio_trim) {
  239. return 0.0f;
  240. }
  241. ret = reverse_mul * (float)(radio_in - radio_trim) / (float)(radio_max - radio_trim);
  242. }
  243. return constrain_float(ret, -1.0f, 1.0f);
  244. }
  245. float
  246. RC_Channel::norm_input_dz() const
  247. {
  248. int16_t dz_min = radio_trim - dead_zone;
  249. int16_t dz_max = radio_trim + dead_zone;
  250. float ret;
  251. int16_t reverse_mul = (reversed?-1:1);
  252. if (radio_in < dz_min && dz_min > radio_min) {
  253. ret = reverse_mul * (float)(radio_in - dz_min) / (float)(dz_min - radio_min);
  254. } else if (radio_in > dz_max && radio_max > dz_max) {
  255. ret = reverse_mul * (float)(radio_in - dz_max) / (float)(radio_max - dz_max);
  256. } else {
  257. ret = 0;
  258. }
  259. return constrain_float(ret, -1.0f, 1.0f);
  260. }
  261. /*
  262. get percentage input from 0 to 100. This ignores the trim value.
  263. */
  264. uint8_t
  265. RC_Channel::percent_input() const
  266. {
  267. if (radio_in <= radio_min) {
  268. return reversed?100:0;
  269. }
  270. if (radio_in >= radio_max) {
  271. return reversed?0:100;
  272. }
  273. uint8_t ret = 100.0f * (radio_in - radio_min) / (float)(radio_max - radio_min);
  274. if (reversed) {
  275. ret = 100 - ret;
  276. }
  277. return ret;
  278. }
  279. /*
  280. return true if input is within deadzone of trim
  281. */
  282. bool RC_Channel::in_trim_dz() const
  283. {
  284. return is_bounded_int32(radio_in, radio_trim - dead_zone, radio_trim + dead_zone);
  285. }
  286. void RC_Channel::set_override(const uint16_t v, const uint32_t timestamp_us)
  287. {
  288. if (!rc().gcs_overrides_enabled()) {
  289. return;
  290. }
  291. last_override_time = timestamp_us != 0 ? timestamp_us : AP_HAL::millis();
  292. override_value = v;
  293. rc().new_override_received();
  294. }
  295. void RC_Channel::clear_override()
  296. {
  297. last_override_time = 0;
  298. override_value = 0;
  299. }
  300. bool RC_Channel::has_override() const
  301. {
  302. if (override_value <= 0) {
  303. return false;
  304. }
  305. const float override_timeout_ms = rc().override_timeout_ms();
  306. return is_positive(override_timeout_ms) && ((AP_HAL::millis() - last_override_time) < (uint32_t)override_timeout_ms);
  307. }
  308. /*
  309. perform stick mixing on one channel
  310. This type of stick mixing reduces the influence of the auto
  311. controller as it increases the influence of the users stick input,
  312. allowing the user full deflection if needed
  313. */
  314. int16_t RC_Channel::stick_mixing(const int16_t servo_in)
  315. {
  316. float ch_inf = (float)(radio_in - radio_trim);
  317. ch_inf = fabsf(ch_inf);
  318. ch_inf = MIN(ch_inf, 400.0f);
  319. ch_inf = ((400.0f - ch_inf) / 400.0f);
  320. int16_t servo_out = servo_in;
  321. servo_out *= ch_inf;
  322. servo_out += control_in;
  323. return servo_out;
  324. }
  325. //
  326. // support for auxillary switches:
  327. //
  328. void RC_Channel::reset_mode_switch()
  329. {
  330. switch_state.current_position = -1;
  331. switch_state.debounce_position = -1;
  332. read_mode_switch();
  333. }
  334. void RC_Channel::read_mode_switch()
  335. {
  336. // calculate position of flight mode switch
  337. const uint16_t pulsewidth = get_radio_in();
  338. if (pulsewidth <= 900 || pulsewidth >= 2200) {
  339. return; // This is an error condition
  340. }
  341. modeswitch_pos_t position;
  342. if (pulsewidth < 1231) position = 0;
  343. else if (pulsewidth < 1361) position = 1;
  344. else if (pulsewidth < 1491) position = 2;
  345. else if (pulsewidth < 1621) position = 3;
  346. else if (pulsewidth < 1750) position = 4;
  347. else position = 5;
  348. if (!debounce_completed(position)) {
  349. return;
  350. }
  351. // set flight mode and simple mode setting
  352. mode_switch_changed(position);
  353. }
  354. bool RC_Channel::debounce_completed(int8_t position)
  355. {
  356. // switch change not detected
  357. if (switch_state.current_position == position) {
  358. // reset debouncing
  359. switch_state.debounce_position = position;
  360. } else {
  361. // switch change detected
  362. const uint32_t tnow_ms = AP_HAL::millis();
  363. // position not established yet
  364. if (switch_state.debounce_position != position) {
  365. switch_state.debounce_position = position;
  366. switch_state.last_edge_time_ms = tnow_ms;
  367. } else if (tnow_ms - switch_state.last_edge_time_ms >= SWITCH_DEBOUNCE_TIME_MS) {
  368. // position estabilished; debounce completed
  369. switch_state.current_position = position;
  370. return true;
  371. }
  372. }
  373. return false;
  374. }
  375. //
  376. // support for auxillary switches:
  377. //
  378. // init_aux_switch_function - initialize aux functions
  379. void RC_Channel::init_aux_function(const aux_func_t ch_option, const aux_switch_pos_t ch_flag)
  380. {
  381. // init channel options
  382. switch(ch_option) {
  383. case AUX_FUNC::FENCE:
  384. case AUX_FUNC::RC_OVERRIDE_ENABLE:
  385. case AUX_FUNC::AVOID_PROXIMITY:
  386. case AUX_FUNC::MISSION_RESET:
  387. do_aux_function(ch_option, ch_flag);
  388. break;
  389. // the following functions do not need to be initialised:
  390. case AUX_FUNC::RELAY:
  391. case AUX_FUNC::RELAY2:
  392. case AUX_FUNC::RELAY3:
  393. case AUX_FUNC::RELAY4:
  394. case AUX_FUNC::RELAY5:
  395. case AUX_FUNC::RELAY6:
  396. case AUX_FUNC::CAMERA_TRIGGER:
  397. case AUX_FUNC::LOST_VEHICLE_SOUND:
  398. case AUX_FUNC::DO_NOTHING:
  399. case AUX_FUNC::CLEAR_WP:
  400. case AUX_FUNC::COMPASS_LEARN:
  401. case AUX_FUNC::LANDING_GEAR:
  402. break;
  403. case AUX_FUNC::MOTOR_ESTOP:
  404. case AUX_FUNC::GRIPPER:
  405. case AUX_FUNC::SPRAYER:
  406. case AUX_FUNC::GPS_DISABLE:
  407. case AUX_FUNC::KILL_IMU1:
  408. case AUX_FUNC::KILL_IMU2:
  409. do_aux_function(ch_option, ch_flag);
  410. break;
  411. default:
  412. gcs().send_text(MAV_SEVERITY_WARNING, "Failed to initialise RC function (%u)", (unsigned)ch_option);
  413. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  414. AP_HAL::panic("RC function (%u) initialisation not handled", (unsigned)ch_option);
  415. #endif
  416. break;
  417. }
  418. }
  419. /*
  420. read an aux channel. Return true if a switch has changed
  421. */
  422. bool RC_Channel::read_aux()
  423. {
  424. const aux_func_t _option = (aux_func_t)option.get();
  425. if (_option == AUX_FUNC::DO_NOTHING) {
  426. // may wish to add special cases for other "AUXSW" things
  427. // here e.g. RCMAP_ROLL etc once they become options
  428. return false;
  429. }
  430. aux_switch_pos_t new_position;
  431. if (!read_3pos_switch(new_position)) {
  432. return false;
  433. }
  434. if (!debounce_completed(new_position)) {
  435. return false;
  436. }
  437. // debounced; undertake the action:
  438. do_aux_function(_option, new_position);
  439. return true;
  440. }
  441. void RC_Channel::do_aux_function_avoid_proximity(const aux_switch_pos_t ch_flag)
  442. {
  443. AC_Avoid *avoid = AP::ac_avoid();
  444. if (avoid == nullptr) {
  445. return;
  446. }
  447. switch (ch_flag) {
  448. case HIGH:
  449. avoid->proximity_avoidance_enable(true);
  450. break;
  451. case MIDDLE:
  452. // nothing
  453. break;
  454. case LOW:
  455. avoid->proximity_avoidance_enable(false);
  456. break;
  457. }
  458. }
  459. void RC_Channel::do_aux_function_camera_trigger(const aux_switch_pos_t ch_flag)
  460. {
  461. AP_Camera *camera = AP::camera();
  462. if (camera == nullptr) {
  463. return;
  464. }
  465. if (ch_flag == HIGH) {
  466. camera->take_picture();
  467. }
  468. }
  469. // enable or disable the fence
  470. void RC_Channel::do_aux_function_fence(const aux_switch_pos_t ch_flag)
  471. {
  472. AC_Fence *fence = AP::fence();
  473. if (fence == nullptr) {
  474. return;
  475. }
  476. AP_Logger *logger = AP_Logger::get_singleton();
  477. if (ch_flag == HIGH) {
  478. fence->enable(true);
  479. if (logger != nullptr) {
  480. logger->Write_Event(DATA_FENCE_ENABLE);
  481. }
  482. } else {
  483. fence->enable(false);
  484. if (logger != nullptr) {
  485. logger->Write_Event(DATA_FENCE_DISABLE);
  486. }
  487. }
  488. }
  489. void RC_Channel::do_aux_function_clear_wp(const aux_switch_pos_t ch_flag)
  490. {
  491. AP_Mission *mission = AP::mission();
  492. if (mission == nullptr) {
  493. return;
  494. }
  495. if (ch_flag == HIGH) {
  496. mission->clear();
  497. }
  498. }
  499. void RC_Channel::do_aux_function_relay(const uint8_t relay, bool val)
  500. {
  501. AP_ServoRelayEvents *servorelayevents = AP::servorelayevents();
  502. if (servorelayevents == nullptr) {
  503. return;
  504. }
  505. servorelayevents->do_set_relay(relay, val);
  506. }
  507. void RC_Channel::do_aux_function_sprayer(const aux_switch_pos_t ch_flag)
  508. {
  509. AC_Sprayer *sprayer = AP::sprayer();
  510. if (sprayer == nullptr) {
  511. return;
  512. }
  513. sprayer->run(ch_flag == HIGH);
  514. // if we are disarmed the pilot must want to test the pump
  515. sprayer->test_pump((ch_flag == HIGH) && !hal.util->get_soft_armed());
  516. }
  517. void RC_Channel::do_aux_function_gripper(const aux_switch_pos_t ch_flag)
  518. {
  519. AP_Gripper *gripper = AP::gripper();
  520. if (gripper == nullptr) {
  521. return;
  522. }
  523. switch(ch_flag) {
  524. case LOW:
  525. gripper->release();
  526. // copter.Log_Write_Event(DATA_GRIPPER_RELEASE);
  527. break;
  528. case MIDDLE:
  529. // nothing
  530. break;
  531. case HIGH:
  532. gripper->grab();
  533. // copter.Log_Write_Event(DATA_GRIPPER_GRAB);
  534. break;
  535. }
  536. }
  537. void RC_Channel::do_aux_function_lost_vehicle_sound(const aux_switch_pos_t ch_flag)
  538. {
  539. switch (ch_flag) {
  540. case HIGH:
  541. AP_Notify::flags.vehicle_lost = true;
  542. break;
  543. case MIDDLE:
  544. // nothing
  545. break;
  546. case LOW:
  547. AP_Notify::flags.vehicle_lost = false;
  548. break;
  549. }
  550. }
  551. void RC_Channel::do_aux_function_rc_override_enable(const aux_switch_pos_t ch_flag)
  552. {
  553. switch (ch_flag) {
  554. case HIGH: {
  555. rc().set_gcs_overrides_enabled(true);
  556. break;
  557. }
  558. case MIDDLE:
  559. // nothing
  560. break;
  561. case LOW: {
  562. rc().set_gcs_overrides_enabled(false);
  563. break;
  564. }
  565. }
  566. }
  567. void RC_Channel::do_aux_function_mission_reset(const aux_switch_pos_t ch_flag)
  568. {
  569. if (ch_flag != HIGH) {
  570. return;
  571. }
  572. AP_Mission *mission = AP::mission();
  573. if (mission == nullptr) {
  574. return;
  575. }
  576. mission->reset();
  577. }
  578. void RC_Channel::do_aux_function(const aux_func_t ch_option, const aux_switch_pos_t ch_flag)
  579. {
  580. switch(ch_option) {
  581. case AUX_FUNC::CAMERA_TRIGGER:
  582. do_aux_function_camera_trigger(ch_flag);
  583. break;
  584. case AUX_FUNC::FENCE:
  585. do_aux_function_fence(ch_flag);
  586. break;
  587. case AUX_FUNC::GRIPPER:
  588. do_aux_function_gripper(ch_flag);
  589. break;
  590. case AUX_FUNC::RC_OVERRIDE_ENABLE:
  591. // Allow or disallow RC_Override
  592. do_aux_function_rc_override_enable(ch_flag);
  593. break;
  594. case AUX_FUNC::AVOID_PROXIMITY:
  595. do_aux_function_avoid_proximity(ch_flag);
  596. break;
  597. case AUX_FUNC::RELAY:
  598. do_aux_function_relay(0, ch_flag == HIGH);
  599. break;
  600. case AUX_FUNC::RELAY2:
  601. do_aux_function_relay(1, ch_flag == HIGH);
  602. break;
  603. case AUX_FUNC::RELAY3:
  604. do_aux_function_relay(2, ch_flag == HIGH);
  605. break;
  606. case AUX_FUNC::RELAY4:
  607. do_aux_function_relay(3, ch_flag == HIGH);
  608. break;
  609. case AUX_FUNC::RELAY5:
  610. do_aux_function_relay(4, ch_flag == HIGH);
  611. break;
  612. case AUX_FUNC::RELAY6:
  613. do_aux_function_relay(5, ch_flag == HIGH);
  614. break;
  615. case AUX_FUNC::CLEAR_WP:
  616. do_aux_function_clear_wp(ch_flag);
  617. break;
  618. case AUX_FUNC::MISSION_RESET:
  619. do_aux_function_mission_reset(ch_flag);
  620. break;
  621. case AUX_FUNC::SPRAYER:
  622. do_aux_function_sprayer(ch_flag);
  623. break;
  624. case AUX_FUNC::LOST_VEHICLE_SOUND:
  625. do_aux_function_lost_vehicle_sound(ch_flag);
  626. break;
  627. case AUX_FUNC::ARMDISARM:
  628. // arm or disarm the vehicle
  629. switch (ch_flag) {
  630. case HIGH:
  631. AP::arming().arm(AP_Arming::Method::AUXSWITCH, true);
  632. break;
  633. case MIDDLE:
  634. // nothing
  635. break;
  636. case LOW:
  637. AP::arming().disarm();
  638. break;
  639. }
  640. break;
  641. case AUX_FUNC::COMPASS_LEARN:
  642. if (ch_flag == HIGH) {
  643. Compass &compass = AP::compass();
  644. compass.set_learn_type(Compass::LEARN_INFLIGHT, false);
  645. }
  646. break;
  647. case AUX_FUNC::LANDING_GEAR: {
  648. AP_LandingGear *lg = AP_LandingGear::get_singleton();
  649. if (lg == nullptr) {
  650. break;
  651. }
  652. switch (ch_flag) {
  653. case LOW:
  654. lg->set_position(AP_LandingGear::LandingGear_Deploy);
  655. break;
  656. case MIDDLE:
  657. // nothing
  658. break;
  659. case HIGH:
  660. lg->set_position(AP_LandingGear::LandingGear_Retract);
  661. break;
  662. }
  663. break;
  664. }
  665. case AUX_FUNC::GPS_DISABLE:
  666. AP::gps().force_disable(ch_flag == HIGH);
  667. break;
  668. case AUX_FUNC::MOTOR_ESTOP:
  669. switch (ch_flag) {
  670. case HIGH: {
  671. SRV_Channels::set_emergency_stop(true);
  672. // log E-stop
  673. AP_Logger *logger = AP_Logger::get_singleton();
  674. if (logger && logger->logging_enabled()) {
  675. logger->Write_Event(DATA_MOTORS_EMERGENCY_STOPPED);
  676. }
  677. break;
  678. }
  679. case MIDDLE:
  680. // nothing
  681. break;
  682. case LOW: {
  683. SRV_Channels::set_emergency_stop(false);
  684. // log E-stop cleared
  685. AP_Logger *logger = AP_Logger::get_singleton();
  686. if (logger && logger->logging_enabled()) {
  687. logger->Write_Event(DATA_MOTORS_EMERGENCY_STOP_CLEARED);
  688. }
  689. break;
  690. }
  691. }
  692. break;
  693. #if !HAL_MINIMIZE_FEATURES
  694. case AUX_FUNC::KILL_IMU1:
  695. if (ch_flag == HIGH) {
  696. AP::ins().kill_imu(0, true);
  697. } else {
  698. AP::ins().kill_imu(0, false);
  699. }
  700. break;
  701. case AUX_FUNC::KILL_IMU2:
  702. if (ch_flag == HIGH) {
  703. AP::ins().kill_imu(1, true);
  704. } else {
  705. AP::ins().kill_imu(1, false);
  706. }
  707. break;
  708. #endif // HAL_MINIMIZE_FEATURES
  709. default:
  710. gcs().send_text(MAV_SEVERITY_INFO, "Invalid channel option (%u)", (unsigned int)ch_option);
  711. break;
  712. }
  713. }
  714. void RC_Channel::init_aux()
  715. {
  716. aux_switch_pos_t position;
  717. if (!read_3pos_switch(position)) {
  718. position = aux_switch_pos_t::LOW;
  719. }
  720. init_aux_function((aux_func_t)option.get(), position);
  721. }
  722. // read_3pos_switch
  723. bool RC_Channel::read_3pos_switch(RC_Channel::aux_switch_pos_t &ret) const
  724. {
  725. const uint16_t in = get_radio_in();
  726. if (in <= 900 or in >= 2200) {
  727. return false;
  728. }
  729. if (in < AUX_PWM_TRIGGER_LOW) {
  730. ret = LOW;
  731. } else if (in > AUX_PWM_TRIGGER_HIGH) {
  732. ret = HIGH;
  733. } else {
  734. ret = MIDDLE;
  735. }
  736. return true;
  737. }
  738. RC_Channel *RC_Channels::find_channel_for_option(const RC_Channel::aux_func_t option)
  739. {
  740. for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
  741. RC_Channel *c = channel(i);
  742. if (c == nullptr) {
  743. // odd?
  744. continue;
  745. }
  746. if ((RC_Channel::aux_func_t)c->option.get() == option) {
  747. return c;
  748. }
  749. }
  750. return nullptr;
  751. }
  752. // duplicate_options_exist - returns true if any options are duplicated
  753. bool RC_Channels::duplicate_options_exist()
  754. {
  755. uint8_t auxsw_option_counts[256] = {};
  756. for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
  757. const RC_Channel *c = channel(i);
  758. if (c == nullptr) {
  759. // odd?
  760. continue;
  761. }
  762. const uint16_t option = c->option.get();
  763. if (option >= sizeof(auxsw_option_counts)) {
  764. continue;
  765. }
  766. auxsw_option_counts[option]++;
  767. }
  768. for (uint16_t i=0; i<sizeof(auxsw_option_counts); i++) {
  769. if (i == 0) { // MAGIC VALUE! This is AUXSW_DO_NOTHING
  770. continue;
  771. }
  772. if (auxsw_option_counts[i] > 1) {
  773. return true;
  774. }
  775. }
  776. return false;
  777. }