SRV_Channel.h 21 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547
  1. /*
  2. control of servo output ranges, trim and servo reversal. This can
  3. optionally be used to provide separation of input and output channel
  4. ranges so that RCn_MIN, RCn_MAX, RCn_TRIM and RCn_REV only apply to
  5. the input side of RC_Channel
  6. It works by running servo output calculations as normal, then
  7. re-mapping the output according to the servo MIN/MAX/TRIM/REV from
  8. this object
  9. Only 4 channels of ranges are defined as those match the input
  10. channels for R/C sticks
  11. */
  12. #pragma once
  13. #include <AP_Common/AP_Common.h>
  14. #include <AP_Param/AP_Param.h>
  15. #include <AP_RCMapper/AP_RCMapper.h>
  16. #include <AP_Common/Bitmask.h>
  17. #include <AP_Volz_Protocol/AP_Volz_Protocol.h>
  18. #include <AP_RobotisServo/AP_RobotisServo.h>
  19. #include <AP_SBusOut/AP_SBusOut.h>
  20. #include <AP_BLHeli/AP_BLHeli.h>
  21. #define NUM_SERVO_CHANNELS 16
  22. class SRV_Channels;
  23. /*
  24. class SRV_Channel. The class SRV_Channels contains an array of
  25. SRV_Channel objects. This is done to fit within the AP_Param limit
  26. of 64 parameters per object.
  27. */
  28. class SRV_Channel {
  29. public:
  30. friend class SRV_Channels;
  31. // constructor
  32. SRV_Channel(void);
  33. static const struct AP_Param::GroupInfo var_info[];
  34. typedef enum
  35. {
  36. k_none = 0, ///< disabled
  37. k_manual = 1, ///< manual, just pass-thru the RC in signal
  38. k_flap = 2, ///< flap
  39. k_flap_auto = 3, ///< flap automated
  40. k_aileron = 4, ///< aileron
  41. k_unused1 = 5, ///< unused function
  42. k_mount_pan = 6, ///< mount yaw (pan)
  43. k_mount_tilt = 7, ///< mount pitch (tilt)
  44. k_mount_roll = 8, ///< mount roll
  45. k_mount_open = 9, ///< mount open (deploy) / close (retract)
  46. k_cam_trigger = 10, ///< camera trigger
  47. k_egg_drop = 11, ///< egg drop
  48. k_mount2_pan = 12, ///< mount2 yaw (pan)
  49. k_mount2_tilt = 13, ///< mount2 pitch (tilt)
  50. k_mount2_roll = 14, ///< mount2 roll
  51. k_mount2_open = 15, ///< mount2 open (deploy) / close (retract)
  52. k_dspoilerLeft1 = 16, ///< differential spoiler 1 (left wing)
  53. k_dspoilerRight1 = 17, ///< differential spoiler 1 (right wing)
  54. k_aileron_with_input = 18, ///< aileron, with rc input, deprecated
  55. k_elevator = 19, ///< elevator
  56. k_elevator_with_input = 20, ///< elevator, with rc input, deprecated
  57. k_rudder = 21, ///< secondary rudder channel
  58. k_sprayer_pump = 22, ///< crop sprayer pump channel
  59. k_sprayer_spinner = 23, ///< crop sprayer spinner channel
  60. k_flaperon_left = 24, ///< flaperon, left wing
  61. k_flaperon_right = 25, ///< flaperon, right wing
  62. k_steering = 26, ///< ground steering, used to separate from rudder
  63. k_parachute_release = 27, ///< parachute release
  64. k_gripper = 28, ///< gripper
  65. k_landing_gear_control = 29, ///< landing gear controller
  66. k_engine_run_enable = 30, ///< engine kill switch, used for gas airplanes and helicopters
  67. k_heli_rsc = 31, ///< helicopter RSC output
  68. k_heli_tail_rsc = 32, ///< helicopter tail RSC output
  69. k_motor1 = 33, ///< these allow remapping of copter motors
  70. k_motor2 = 34,
  71. k_motor3 = 35,
  72. k_motor4 = 36,
  73. k_motor5 = 37,
  74. k_motor6 = 38,
  75. k_motor7 = 39,
  76. k_motor8 = 40,
  77. k_motor_tilt = 41, ///< tiltrotor motor tilt control
  78. k_rcin1 = 51, ///< these are for pass-thru from arbitrary rc inputs
  79. k_rcin2 = 52,
  80. k_rcin3 = 53,
  81. k_rcin4 = 54,
  82. k_rcin5 = 55,
  83. k_rcin6 = 56,
  84. k_rcin7 = 57,
  85. k_rcin8 = 58,
  86. k_rcin9 = 59,
  87. k_rcin10 = 60,
  88. k_rcin11 = 61,
  89. k_rcin12 = 62,
  90. k_rcin13 = 63,
  91. k_rcin14 = 64,
  92. k_rcin15 = 65,
  93. k_rcin16 = 66,
  94. k_ignition = 67,
  95. k_choke = 68,
  96. k_starter = 69,
  97. k_throttle = 70,
  98. k_tracker_yaw = 71, ///< antennatracker yaw
  99. k_tracker_pitch = 72, ///< antennatracker pitch
  100. k_throttleLeft = 73,
  101. k_throttleRight = 74,
  102. k_tiltMotorLeft = 75, ///< vectored thrust, left tilt
  103. k_tiltMotorRight = 76, ///< vectored thrust, right tilt
  104. k_elevon_left = 77,
  105. k_elevon_right = 78,
  106. k_vtail_left = 79,
  107. k_vtail_right = 80,
  108. k_boost_throttle = 81, ///< vertical booster throttle
  109. k_motor9 = 82,
  110. k_motor10 = 83,
  111. k_motor11 = 84,
  112. k_motor12 = 85,
  113. k_dspoilerLeft2 = 86, ///< differential spoiler 2 (left wing)
  114. k_dspoilerRight2 = 87, ///< differential spoiler 2 (right wing)
  115. k_winch = 88,
  116. k_mainsail_sheet = 89, ///< Main Sail control via sheet
  117. k_cam_iso = 90,
  118. k_cam_aperture = 91,
  119. k_cam_focus = 92,
  120. k_cam_shutter_speed = 93,
  121. k_scripting1 = 94, ///< Scripting related outputs
  122. k_scripting2 = 95,
  123. k_scripting3 = 96,
  124. k_scripting4 = 97,
  125. k_scripting5 = 98,
  126. k_scripting6 = 99,
  127. k_scripting7 = 100,
  128. k_scripting8 = 101,
  129. k_scripting9 = 102,
  130. k_scripting10 = 103,
  131. k_scripting11 = 104,
  132. k_scripting12 = 105,
  133. k_scripting13 = 106,
  134. k_scripting14 = 107,
  135. k_scripting15 = 108,
  136. k_scripting16 = 109,
  137. k_LED_neopixel1 = 120,
  138. k_LED_neopixel2 = 121,
  139. k_LED_neopixel3 = 122,
  140. k_LED_neopixel4 = 123,
  141. k_nr_aux_servo_functions ///< This must be the last enum value (only add new values _before_ this one)
  142. } Aux_servo_function_t;
  143. // used to get min/max/trim limit value based on reverse
  144. enum LimitValue {
  145. SRV_CHANNEL_LIMIT_TRIM,
  146. SRV_CHANNEL_LIMIT_MIN,
  147. SRV_CHANNEL_LIMIT_MAX,
  148. SRV_CHANNEL_LIMIT_ZERO_PWM
  149. };
  150. // set the output value as a pwm value
  151. void set_output_pwm(uint16_t pwm);
  152. // get the output value as a pwm value
  153. uint16_t get_output_pwm(void) const { return output_pwm; }
  154. // set angular range of scaled output
  155. void set_angle(int16_t angle);
  156. // set range of scaled output. Low is always zero
  157. void set_range(uint16_t high);
  158. // return true if the channel is reversed
  159. bool get_reversed(void) const {
  160. return reversed?true:false;
  161. }
  162. // set MIN/MAX parameters
  163. void set_output_min(uint16_t pwm) {
  164. servo_min.set(pwm);
  165. }
  166. void set_output_max(uint16_t pwm) {
  167. servo_max.set(pwm);
  168. }
  169. // get MIN/MAX/TRIM parameters
  170. uint16_t get_output_min(void) const {
  171. return servo_min;
  172. }
  173. uint16_t get_output_max(void) const {
  174. return servo_max;
  175. }
  176. uint16_t get_trim(void) const {
  177. return servo_trim;
  178. }
  179. // return true if function is for a multicopter motor
  180. static bool is_motor(SRV_Channel::Aux_servo_function_t function);
  181. // return true if function is for anything that should be stopped in a e-stop situation, ie is dangerous
  182. static bool should_e_stop(SRV_Channel::Aux_servo_function_t function);
  183. // return the function of a channel
  184. SRV_Channel::Aux_servo_function_t get_function(void) const {
  185. return (SRV_Channel::Aux_servo_function_t)function.get();
  186. }
  187. // set and save function for channel. Used in upgrade of parameters in plane
  188. void function_set_and_save(SRV_Channel::Aux_servo_function_t f) {
  189. function.set_and_save(int8_t(f));
  190. }
  191. // set and save function for reversed. Used in upgrade of parameters in plane
  192. void reversed_set_and_save_ifchanged(bool r) {
  193. reversed.set_and_save_ifchanged(r?1:0);
  194. }
  195. // return true if the SERVOn_FUNCTION has been configured in
  196. // either storage or a defaults file. This is used for upgrade of
  197. // parameters in plane
  198. bool function_configured(void) const {
  199. return function.configured();
  200. }
  201. // specify that small rc input changes should be ignored during passthrough
  202. // used by DO_SET_SERVO commands
  203. void ignore_small_rcin_changes() { ign_small_rcin_changes = true; }
  204. private:
  205. AP_Int16 servo_min;
  206. AP_Int16 servo_max;
  207. AP_Int16 servo_trim;
  208. // reversal, following convention that 1 means reversed, 0 means normal
  209. AP_Int8 reversed;
  210. AP_Int8 function;
  211. // a pending output value as PWM
  212. uint16_t output_pwm;
  213. // true for angle output type
  214. bool type_angle:1;
  215. // set_range() or set_angle() has been called
  216. bool type_setup:1;
  217. // the hal channel number
  218. uint8_t ch_num;
  219. // high point of angle or range output
  220. uint16_t high_out;
  221. // convert a 0..range_max to a pwm
  222. uint16_t pwm_from_range(int16_t scaled_value) const;
  223. // convert a -angle_max..angle_max to a pwm
  224. uint16_t pwm_from_angle(int16_t scaled_value) const;
  225. // convert a scaled output to a pwm value
  226. void calc_pwm(int16_t output_scaled);
  227. // output value based on function
  228. void output_ch(void);
  229. // setup output type and range based on function
  230. void aux_servo_function_setup(void);
  231. // return PWM for a given limit value
  232. uint16_t get_limit_pwm(LimitValue limit) const;
  233. // get normalised output from -1 to 1
  234. float get_output_norm(void);
  235. // a bitmask type wide enough for NUM_SERVO_CHANNELS
  236. typedef uint16_t servo_mask_t;
  237. // mask of channels where we have a output_pwm value. Cleared when a
  238. // scaled value is written.
  239. static servo_mask_t have_pwm_mask;
  240. // previous radio_in during pass-thru
  241. int16_t previous_radio_in;
  242. // specify that small rcinput changes should be ignored during passthrough
  243. // used by DO_SET_SERVO commands
  244. bool ign_small_rcin_changes;
  245. };
  246. /*
  247. class SRV_Channels
  248. */
  249. class SRV_Channels {
  250. public:
  251. friend class SRV_Channel;
  252. // constructor
  253. SRV_Channels(void);
  254. static const struct AP_Param::GroupInfo var_info[];
  255. // set the default function for a channel
  256. static void set_default_function(uint8_t chan, SRV_Channel::Aux_servo_function_t function);
  257. // set output value for a function channel as a pwm value
  258. static void set_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t value);
  259. // set output value for a function channel as a pwm value on the first matching channel
  260. static void set_output_pwm_first(SRV_Channel::Aux_servo_function_t function, uint16_t value);
  261. // set output value for a specific function channel as a pwm value
  262. static void set_output_pwm_chan(uint8_t chan, uint16_t value);
  263. // set output value for a function channel as a scaled value. This
  264. // calls calc_pwm() to also set the pwm value
  265. static void set_output_scaled(SRV_Channel::Aux_servo_function_t function, int16_t value);
  266. // get scaled output for the given function type.
  267. static int16_t get_output_scaled(SRV_Channel::Aux_servo_function_t function);
  268. // get pwm output for the first channel of the given function type.
  269. static bool get_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t &value);
  270. // get normalised output (-1 to 1 for angle, 0 to 1 for range). Value is taken from pwm value
  271. // return zero on error.
  272. static float get_output_norm(SRV_Channel::Aux_servo_function_t function);
  273. // get output channel mask for a function
  274. static uint16_t get_output_channel_mask(SRV_Channel::Aux_servo_function_t function);
  275. // limit slew rate to given limit in percent per second
  276. static void limit_slew_rate(SRV_Channel::Aux_servo_function_t function, float slew_rate, float dt);
  277. // call output_ch() on all channels
  278. static void output_ch_all(void);
  279. // setup output ESC scaling based on a channels MIN/MAX
  280. void set_esc_scaling_for(SRV_Channel::Aux_servo_function_t function);
  281. // return true when auto_trim enabled
  282. bool auto_trim_enabled(void) const { return auto_trim; }
  283. // adjust trim of a channel by a small increment
  284. void adjust_trim(SRV_Channel::Aux_servo_function_t function, float v);
  285. // set MIN/MAX parameters for a function
  286. static void set_output_min_max(SRV_Channel::Aux_servo_function_t function, uint16_t min_pwm, uint16_t max_pwm);
  287. // save trims
  288. void save_trim(void);
  289. // setup for a reversible k_throttle (from -100 to 100)
  290. void set_reversible_throttle(void) {
  291. flags.k_throttle_reversible = true;
  292. }
  293. // setup IO failsafe for all channels to trim
  294. static void setup_failsafe_trim_all_non_motors(void);
  295. // set output for all channels matching the given function type, allow radio_trim to center servo
  296. static void set_output_pwm_trimmed(SRV_Channel::Aux_servo_function_t function, int16_t value);
  297. // set and save the trim for a function channel to the output value
  298. static void set_trim_to_servo_out_for(SRV_Channel::Aux_servo_function_t function);
  299. // set the trim for a function channel to min of the channel
  300. static void set_trim_to_min_for(SRV_Channel::Aux_servo_function_t function);
  301. // set the trim for a function channel to given pwm
  302. static void set_trim_to_pwm_for(SRV_Channel::Aux_servo_function_t function, int16_t pwm);
  303. // set output to min value
  304. static void set_output_to_min(SRV_Channel::Aux_servo_function_t function);
  305. // set output to max value
  306. static void set_output_to_max(SRV_Channel::Aux_servo_function_t function);
  307. // set output to trim value
  308. static void set_output_to_trim(SRV_Channel::Aux_servo_function_t function);
  309. // copy radio_in to servo out
  310. static void copy_radio_in_out(SRV_Channel::Aux_servo_function_t function, bool do_input_output=false);
  311. // copy radio_in to servo_out by channel mask
  312. static void copy_radio_in_out_mask(uint16_t mask);
  313. // setup failsafe for an auxiliary channel function, by pwm
  314. static void set_failsafe_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t pwm);
  315. // setup failsafe for an auxiliary channel function
  316. static void set_failsafe_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit);
  317. // setup safety for an auxiliary channel function (used when disarmed)
  318. static void set_safety_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit);
  319. // set servo to a LimitValue
  320. static void set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit);
  321. // return true if a function is assigned to a channel
  322. static bool function_assigned(SRV_Channel::Aux_servo_function_t function);
  323. // set a servo_out value, and angle range, then calc_pwm
  324. static void move_servo(SRV_Channel::Aux_servo_function_t function,
  325. int16_t value, int16_t angle_min, int16_t angle_max);
  326. // assign and enable auxiliary channels
  327. static void enable_aux_servos(void);
  328. // enable channels by mask
  329. static void enable_by_mask(uint16_t mask);
  330. // return the current function for a channel
  331. static SRV_Channel::Aux_servo_function_t channel_function(uint8_t channel);
  332. // refresh aux servo to function mapping
  333. static void update_aux_servo_function(void);
  334. // set default channel for an auxiliary function
  335. static bool set_aux_channel_default(SRV_Channel::Aux_servo_function_t function, uint8_t channel);
  336. // find first channel that a function is assigned to
  337. static bool find_channel(SRV_Channel::Aux_servo_function_t function, uint8_t &chan);
  338. // find first channel that a function is assigned to, returning SRV_Channel object
  339. static SRV_Channel *get_channel_for(SRV_Channel::Aux_servo_function_t function, int8_t default_chan=-1);
  340. // call set_angle() on matching channels
  341. static void set_angle(SRV_Channel::Aux_servo_function_t function, uint16_t angle);
  342. // call set_range() on matching channels
  343. static void set_range(SRV_Channel::Aux_servo_function_t function, uint16_t range);
  344. // set output refresh frequency on a servo function
  345. static void set_rc_frequency(SRV_Channel::Aux_servo_function_t function, uint16_t frequency);
  346. // control pass-thru of channels
  347. void disable_passthrough(bool disable) {
  348. disabled_passthrough = disable;
  349. }
  350. // constrain to output min/max for function
  351. static void constrain_pwm(SRV_Channel::Aux_servo_function_t function);
  352. // calculate PWM for all channels
  353. static void calc_pwm(void);
  354. static SRV_Channel *srv_channel(uint8_t i) {
  355. return i<NUM_SERVO_CHANNELS?&channels[i]:nullptr;
  356. }
  357. // upgrade RC* parameters into SERVO* parameters
  358. static bool upgrade_parameters(const uint8_t old_keys[14], uint16_t aux_channel_mask, RCMapper *rcmap);
  359. static void upgrade_motors_servo(uint8_t ap_motors_key, uint8_t ap_motors_idx, uint8_t new_channel);
  360. // given a zero-based motor channel, return the k_motor function for that channel
  361. static SRV_Channel::Aux_servo_function_t get_motor_function(uint8_t channel) {
  362. if (channel < 8) {
  363. return SRV_Channel::Aux_servo_function_t(SRV_Channel::k_motor1+channel);
  364. }
  365. return SRV_Channel::Aux_servo_function_t((SRV_Channel::k_motor9+(channel-8)));
  366. }
  367. static void cork();
  368. static void push();
  369. // disable output to a set of channels given by a mask. This is used by the AP_BLHeli code
  370. static void set_disabled_channel_mask(uint16_t mask) { disabled_mask = mask; }
  371. // add to mask of outputs which can do reverse thrust using digital controls
  372. static void set_reversible_mask(uint16_t mask) {
  373. reversible_mask |= mask;
  374. }
  375. // add to mask of outputs which use digital (non-PWM) output, such as DShot
  376. static void set_digital_mask(uint16_t mask) {
  377. digital_mask |= mask;
  378. }
  379. // Set E - stop
  380. static void set_emergency_stop(bool state) {
  381. emergency_stop = state;
  382. }
  383. // get E - stop
  384. static bool get_emergency_stop() { return emergency_stop;}
  385. private:
  386. struct {
  387. bool k_throttle_reversible:1;
  388. } flags;
  389. static bool disabled_passthrough;
  390. SRV_Channel::servo_mask_t trimmed_mask;
  391. static Bitmask<SRV_Channel::k_nr_aux_servo_functions> function_mask;
  392. static bool initialised;
  393. // this static arrangement is to avoid having static objects in AP_Param tables
  394. static SRV_Channel *channels;
  395. static SRV_Channels *_singleton;
  396. // support for Volz protocol
  397. AP_Volz_Protocol volz;
  398. static AP_Volz_Protocol *volz_ptr;
  399. // support for SBUS protocol
  400. AP_SBusOut sbus;
  401. static AP_SBusOut *sbus_ptr;
  402. // support for Robotis servo protocol
  403. AP_RobotisServo robotis;
  404. static AP_RobotisServo *robotis_ptr;
  405. #if HAL_SUPPORT_RCOUT_SERIAL
  406. // support for BLHeli protocol
  407. AP_BLHeli blheli;
  408. static AP_BLHeli *blheli_ptr;
  409. #endif
  410. static uint16_t disabled_mask;
  411. // mask of outputs which use a digital output protocol, not
  412. // PWM (eg. DShot)
  413. static uint16_t digital_mask;
  414. // mask of outputs which are digitally reversible (eg. DShot-3D)
  415. static uint16_t reversible_mask;
  416. SRV_Channel obj_channels[NUM_SERVO_CHANNELS];
  417. static struct srv_function {
  418. // mask of what channels this applies to
  419. SRV_Channel::servo_mask_t channel_mask;
  420. // scaled output for this function
  421. int16_t output_scaled;
  422. } functions[SRV_Channel::k_nr_aux_servo_functions];
  423. AP_Int8 auto_trim;
  424. AP_Int16 default_rate;
  425. // return true if passthrough is disabled
  426. static bool passthrough_disabled(void) {
  427. return disabled_passthrough;
  428. }
  429. static bool emergency_stop;
  430. };