RCOutput.h 6.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212
  1. #pragma once
  2. #include "AP_HAL_Namespace.h"
  3. #include <stdint.h>
  4. #define RC_OUTPUT_MIN_PULSEWIDTH 400
  5. #define RC_OUTPUT_MAX_PULSEWIDTH 2100
  6. /* Define the CH_n names, indexed from 1, if we don't have them already */
  7. #ifndef CH_1
  8. #define CH_1 0
  9. #define CH_2 1
  10. #define CH_3 2
  11. #define CH_4 3
  12. #define CH_5 4
  13. #define CH_6 5
  14. #define CH_7 6
  15. #define CH_8 7
  16. #define CH_9 8
  17. #define CH_10 9
  18. #define CH_11 10
  19. #define CH_12 11
  20. #define CH_13 12
  21. #define CH_14 13
  22. #define CH_15 14
  23. #define CH_16 15
  24. #define CH_17 16
  25. #define CH_18 17
  26. #define CH_NONE 255
  27. #endif
  28. class ByteBuffer;
  29. class AP_HAL::RCOutput {
  30. public:
  31. virtual void init() = 0;
  32. /* Output freq (1/period) control */
  33. virtual void set_freq(uint32_t chmask, uint16_t freq_hz) = 0;
  34. virtual uint16_t get_freq(uint8_t chan) = 0;
  35. /* Output active/highZ control, either by single channel at a time
  36. * or a mask of channels */
  37. virtual void enable_ch(uint8_t chan) = 0;
  38. virtual void disable_ch(uint8_t chan) = 0;
  39. /*
  40. * Output a single channel, possibly grouped with previous writes if
  41. * cork() has been called before.
  42. */
  43. virtual void write(uint8_t chan, uint16_t period_us) = 0;
  44. /*
  45. * mark the channels in chanmask as reversible. This is needed for some ESC types (such as DShot)
  46. * so that output scaling can be performed correctly. The chanmask passed is added (ORed) into
  47. * any existing mask.
  48. */
  49. virtual void set_reversible_mask(uint16_t chanmask) {}
  50. /*
  51. * Delay subsequent calls to write() going to the underlying hardware in
  52. * order to group related writes together. When all the needed writes are
  53. * done, call push() to commit the changes.
  54. */
  55. virtual void cork() = 0;
  56. /*
  57. * Push pending changes to the underlying hardware. All changes between a
  58. * call to cork() and push() are pushed together in a single transaction.
  59. */
  60. virtual void push() = 0;
  61. /* Read back current output state, as either single channel or
  62. * array of channels. On boards that have a separate IO controller,
  63. * this returns the latest output value that the IO controller has
  64. * reported */
  65. virtual uint16_t read(uint8_t chan) = 0;
  66. virtual void read(uint16_t* period_us, uint8_t len) = 0;
  67. /* Read the current input state. This returns the last value that was written. */
  68. virtual uint16_t read_last_sent(uint8_t chan) { return read(chan); }
  69. virtual void read_last_sent(uint16_t* period_us, uint8_t len) { read(period_us, len); };
  70. /*
  71. set PWM to send to a set of channels when the safety switch is
  72. in the safe state
  73. */
  74. virtual void set_safety_pwm(uint32_t chmask, uint16_t period_us) {}
  75. /*
  76. set PWM to send to a set of channels if the FMU firmware dies
  77. */
  78. virtual void set_failsafe_pwm(uint32_t chmask, uint16_t period_us) {}
  79. /*
  80. force the safety switch on, disabling PWM output from the IO board
  81. return false (indicating failure) by default so that boards with no safety switch
  82. do not need to implement this method
  83. */
  84. virtual bool force_safety_on(void) { return false; }
  85. /*
  86. force the safety switch off, enabling PWM output from the IO board
  87. */
  88. virtual void force_safety_off(void) {}
  89. /*
  90. setup scaling of ESC output for ESCs that can output a
  91. percentage of power (such as UAVCAN ESCs). The values are in
  92. microseconds, and represent minimum and maximum PWM values which
  93. will be used to convert channel writes into a percentage
  94. */
  95. virtual void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) {}
  96. /*
  97. return ESC scaling value from set_esc_scaling()
  98. */
  99. virtual bool get_esc_scaling(uint16_t &min_pwm, uint16_t &max_pwm) { return false; }
  100. /*
  101. returns the pwm value scaled to [-1;1] regrading to set_esc_scaling ranges range without constraints.
  102. */
  103. virtual float scale_esc_to_unity(uint16_t pwm) { return 0; }
  104. /*
  105. enable PX4IO SBUS out at the given rate
  106. */
  107. virtual bool enable_px4io_sbus_out(uint16_t rate_hz) { return false; }
  108. /*
  109. * Optional method to control the update of the motors. Derived classes
  110. * can implement it if their HAL layer requires.
  111. */
  112. virtual void timer_tick(void) { }
  113. /*
  114. setup for serial output to an ESC using the given
  115. baudrate. Assumes 1 start bit, 1 stop bit, LSB first and 8
  116. databits. This is used for passthrough ESC configuration and
  117. firmware flashing
  118. While serial output is active normal output to all channels in
  119. the chanmask is suspended. Output to some other channels (such
  120. as those in the same channel timer groups) may also be stopped,
  121. depending on the implementation
  122. */
  123. virtual bool serial_setup_output(uint8_t chan, uint32_t baudrate, uint16_t chanmask) { return false; }
  124. /*
  125. write a set of bytes to an ESC, using settings from
  126. serial_setup_output. This is a blocking call
  127. */
  128. virtual bool serial_write_bytes(const uint8_t *bytes, uint16_t len) { return false; }
  129. /*
  130. read a series of bytes from a port, using serial parameters from serial_setup_output()
  131. return the number of bytes read. This is a blocking call
  132. */
  133. virtual uint16_t serial_read_bytes(uint8_t *buf, uint16_t len) { return 0; }
  134. /*
  135. stop serial output. This restores the previous output mode for
  136. the channel and any other channels that were stopped by
  137. serial_setup_output()
  138. */
  139. virtual void serial_end(void) {}
  140. /*
  141. output modes. Allows for support of PWM, oneshot and dshot
  142. */
  143. enum output_mode {
  144. MODE_PWM_NONE,
  145. MODE_PWM_NORMAL,
  146. MODE_PWM_ONESHOT,
  147. MODE_PWM_ONESHOT125,
  148. MODE_PWM_BRUSHED,
  149. MODE_PWM_DSHOT150,
  150. MODE_PWM_DSHOT300,
  151. MODE_PWM_DSHOT600,
  152. MODE_PWM_DSHOT1200,
  153. MODE_NEOPIXEL, // same as MODE_PWM_DSHOT at 800kHz but it's an LED
  154. };
  155. virtual void set_output_mode(uint16_t mask, enum output_mode mode) {}
  156. /*
  157. set default update rate
  158. */
  159. virtual void set_default_rate(uint16_t rate_hz) {}
  160. /*
  161. enable telemetry request for a mask of channels. This is used
  162. with DShot to get telemetry feedback
  163. */
  164. virtual void set_telem_request_mask(uint16_t mask) {}
  165. /*
  166. setup neopixel (WS2812B) output for a given channel number, with
  167. the given max number of LEDs in the chain.
  168. */
  169. virtual bool set_neopixel_num_LEDs(const uint16_t chan, uint8_t num_leds) { return false; }
  170. /*
  171. setup neopixel (WS2812B) output data for a given output channel
  172. and mask of which LEDs in the chain
  173. */
  174. virtual void set_neopixel_rgb_data(const uint16_t chan, uint32_t ledmask, uint8_t red, uint8_t green, uint8_t blue) {}
  175. /*
  176. trigger send of neopixel data
  177. */
  178. virtual void neopixel_send(void) {}
  179. };