AP_IOMCU.h 7.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273
  1. /*
  2. implement protocol for controlling an IO microcontroller
  3. For bootstrapping this will initially implement the px4io protocol,
  4. but will later move to an ArduPilot specific protocol
  5. */
  6. #include <AP_HAL/AP_HAL.h>
  7. #if HAL_WITH_IO_MCU
  8. #include "ch.h"
  9. #include "iofirmware/ioprotocol.h"
  10. #include <AP_RCMapper/AP_RCMapper.h>
  11. class AP_IOMCU {
  12. public:
  13. AP_IOMCU(AP_HAL::UARTDriver &uart);
  14. void init(void);
  15. // write to one channel
  16. void write_channel(uint8_t chan, uint16_t pwm);
  17. // read from one channel
  18. uint16_t read_channel(uint8_t chan);
  19. // cork output
  20. void cork(void);
  21. // push output
  22. void push(void);
  23. // set output frequency
  24. void set_freq(uint16_t chmask, uint16_t freq);
  25. // get output frequency
  26. uint16_t get_freq(uint16_t chan);
  27. // get state of safety switch
  28. AP_HAL::Util::safety_state get_safety_switch_state(void) const;
  29. // force safety on
  30. bool force_safety_on(void);
  31. // force safety off
  32. void force_safety_off(void);
  33. // set PWM of channels when safety is on
  34. void set_safety_pwm(uint16_t chmask, uint16_t period_us);
  35. // set mask of channels that ignore safety state
  36. void set_safety_mask(uint16_t chmask);
  37. // set PWM of channels when in FMU failsafe
  38. void set_failsafe_pwm(uint16_t chmask, uint16_t period_us);
  39. /*
  40. enable sbus output
  41. */
  42. bool enable_sbus_out(uint16_t rate_hz);
  43. /*
  44. check for new RC input
  45. */
  46. bool check_rcinput(uint32_t &last_frame_us, uint8_t &num_channels, uint16_t *channels, uint8_t max_channels);
  47. // Do DSM receiver binding
  48. void bind_dsm(uint8_t mode);
  49. // get the name of the RC protocol
  50. const char *get_rc_protocol(void);
  51. /*
  52. get servo rail voltage
  53. */
  54. float get_vservo(void) const { return reg_status.vservo * 0.001; }
  55. /*
  56. get rssi voltage
  57. */
  58. float get_vrssi(void) const { return reg_status.vrssi * 0.001; }
  59. // set target for IMU heater
  60. void set_heater_duty_cycle(uint8_t duty_cycle);
  61. // set default output rate
  62. void set_default_rate(uint16_t rate_hz);
  63. // set to oneshot mode
  64. void set_oneshot_mode(void);
  65. // set to brushed mode
  66. void set_brushed_mode(void);
  67. // check if IO is healthy
  68. bool healthy(void);
  69. // shutdown IO protocol (for reboot)
  70. void shutdown();
  71. // setup for FMU failsafe mixing
  72. bool setup_mixing(RCMapper *rcmap, int8_t override_chan,
  73. float mixing_gain, uint16_t manual_rc_mask);
  74. // channel group masks
  75. const uint8_t ch_masks[3] = { 0x03,0x0C,0xF0 };
  76. private:
  77. AP_HAL::UARTDriver &uart;
  78. void thread_main(void);
  79. // read count 16 bit registers
  80. bool read_registers(uint8_t page, uint8_t offset, uint8_t count, uint16_t *regs);
  81. // write count 16 bit registers
  82. bool write_registers(uint8_t page, uint8_t offset, uint8_t count, const uint16_t *regs);
  83. // write a single register
  84. bool write_register(uint8_t page, uint8_t offset, uint16_t v) {
  85. return write_registers(page, offset, 1, &v);
  86. }
  87. // modify a single register
  88. bool modify_register(uint8_t page, uint8_t offset, uint16_t clearbits, uint16_t setbits);
  89. // trigger an ioevent
  90. void trigger_event(uint8_t event);
  91. // IOMCU thread
  92. thread_t *thread_ctx;
  93. eventmask_t initial_event_mask;
  94. // time when we last read various pages
  95. uint32_t last_status_read_ms;
  96. uint32_t last_rc_read_ms;
  97. uint32_t last_servo_read_ms;
  98. uint32_t last_safety_option_check_ms;
  99. // last value of safety options
  100. uint16_t last_safety_options = 0xFFFF;
  101. // have we forced the safety off?
  102. bool safety_forced_off;
  103. void send_servo_out(void);
  104. void read_rc_input(void);
  105. void read_servo(void);
  106. void read_status(void);
  107. void discard_input(void);
  108. void event_failed(uint8_t event);
  109. void update_safety_options(void);
  110. // CONFIG page
  111. struct page_config config;
  112. // PAGE_STATUS values
  113. struct page_reg_status reg_status;
  114. uint32_t last_log_ms;
  115. // PAGE_RAW_RCIN values
  116. struct page_rc_input rc_input;
  117. uint32_t rc_last_input_ms;
  118. // MIXER values
  119. struct page_mixing mixing;
  120. // output pwm values
  121. struct {
  122. uint8_t num_channels;
  123. uint16_t pwm[IOMCU_MAX_CHANNELS];
  124. uint8_t safety_pwm_set;
  125. uint8_t safety_pwm_sent;
  126. uint16_t safety_pwm[IOMCU_MAX_CHANNELS];
  127. uint16_t safety_mask;
  128. uint16_t failsafe_pwm[IOMCU_MAX_CHANNELS];
  129. uint8_t failsafe_pwm_set;
  130. uint8_t failsafe_pwm_sent;
  131. } pwm_out;
  132. // read back pwm values
  133. struct {
  134. uint16_t pwm[IOMCU_MAX_CHANNELS];
  135. } pwm_in;
  136. // output rates
  137. struct {
  138. uint16_t freq;
  139. uint16_t chmask;
  140. uint16_t default_freq = 50;
  141. uint16_t sbus_rate_hz;
  142. } rate;
  143. // IMU heater duty cycle
  144. uint8_t heater_duty_cycle;
  145. uint32_t last_servo_out_us;
  146. bool corked;
  147. bool do_shutdown;
  148. bool done_shutdown;
  149. bool crc_is_ok;
  150. bool detected_io_reset;
  151. bool initialised;
  152. bool is_chibios_backend;
  153. uint32_t protocol_fail_count;
  154. uint32_t protocol_count;
  155. uint32_t total_errors;
  156. uint32_t num_delayed;
  157. uint32_t last_iocmu_timestamp_ms;
  158. // firmware upload
  159. const char *fw_name = "io_firmware.bin";
  160. uint8_t *fw;
  161. uint32_t fw_size;
  162. size_t write_wait(const uint8_t *pkt, uint8_t len);
  163. bool upload_fw(void);
  164. bool recv_byte_with_timeout(uint8_t *c, uint32_t timeout_ms);
  165. bool recv_bytes(uint8_t *p, uint32_t count);
  166. void drain(void);
  167. bool send(uint8_t c);
  168. bool send(const uint8_t *p, uint32_t count);
  169. bool get_sync(uint32_t timeout = 40);
  170. bool sync();
  171. bool get_info(uint8_t param, uint32_t &val);
  172. bool erase();
  173. bool program(uint32_t fw_size);
  174. bool verify_rev2(uint32_t fw_size);
  175. bool verify_rev3(uint32_t fw_size_local);
  176. bool reboot();
  177. bool check_crc(void);
  178. void handle_repeated_failures();
  179. void check_iomcu_reset();
  180. enum {
  181. PROTO_NOP = 0x00,
  182. PROTO_OK = 0x10,
  183. PROTO_FAILED = 0x11,
  184. PROTO_INSYNC = 0x12,
  185. PROTO_INVALID = 0x13,
  186. PROTO_BAD_SILICON_REV = 0x14,
  187. PROTO_EOC = 0x20,
  188. PROTO_GET_SYNC = 0x21,
  189. PROTO_GET_DEVICE = 0x22,
  190. PROTO_CHIP_ERASE = 0x23,
  191. PROTO_CHIP_VERIFY = 0x24,
  192. PROTO_PROG_MULTI = 0x27,
  193. PROTO_READ_MULTI = 0x28,
  194. PROTO_GET_CRC = 0x29,
  195. PROTO_GET_OTP = 0x2a,
  196. PROTO_GET_SN = 0x2b,
  197. PROTO_GET_CHIP = 0x2c,
  198. PROTO_SET_DELAY = 0x2d,
  199. PROTO_GET_CHIP_DES = 0x2e,
  200. PROTO_REBOOT = 0x30,
  201. INFO_BL_REV = 1, /**< bootloader protocol revision */
  202. BL_REV = 5, /**< supported bootloader protocol */
  203. INFO_BOARD_ID = 2, /**< board type */
  204. INFO_BOARD_REV = 3, /**< board revision */
  205. INFO_FLASH_SIZE = 4, /**< max firmware size in bytes */
  206. PROG_MULTI_MAX = 248, /**< protocol max is 255, must be multiple of 4 */
  207. };
  208. };
  209. #endif // HAL_WITH_IO_MCU