ioprotocol.h 3.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161
  1. #pragma once
  2. #include <stdint.h>
  3. #include <AP_Common/AP_Common.h>
  4. /*
  5. common protocol definitions between AP_IOMCU and iofirmware
  6. */
  7. // 22 is enough for the rc_input page in one transfer
  8. #define PKT_MAX_REGS 22
  9. #define IOMCU_MAX_CHANNELS 16
  10. //#define IOMCU_DEBUG
  11. struct PACKED IOPacket {
  12. uint8_t count:6;
  13. uint8_t code:2;
  14. uint8_t crc;
  15. uint8_t page;
  16. uint8_t offset;
  17. uint16_t regs[PKT_MAX_REGS];
  18. // get packet size in bytes
  19. uint8_t get_size(void) const
  20. {
  21. return count*2 + 4;
  22. }
  23. };
  24. /*
  25. values for pkt.code
  26. */
  27. enum iocode {
  28. // read types
  29. CODE_READ = 0,
  30. CODE_WRITE = 1,
  31. // reply codes
  32. CODE_SUCCESS = 0,
  33. CODE_CORRUPT = 1,
  34. CODE_ERROR = 2
  35. };
  36. // IO pages
  37. enum iopage {
  38. PAGE_CONFIG = 0,
  39. PAGE_STATUS = 1,
  40. PAGE_ACTUATORS = 2,
  41. PAGE_SERVOS = 3,
  42. PAGE_RAW_RCIN = 4,
  43. PAGE_RCIN = 5,
  44. PAGE_RAW_ADC = 6,
  45. PAGE_PWM_INFO = 7,
  46. PAGE_SETUP = 50,
  47. PAGE_DIRECT_PWM = 54,
  48. PAGE_FAILSAFE_PWM = 55,
  49. PAGE_SAFETY_PWM = 108,
  50. PAGE_MIXING = 200,
  51. };
  52. // setup page registers
  53. #define PAGE_REG_SETUP_FEATURES 0
  54. #define P_SETUP_FEATURES_SBUS1_OUT 1
  55. #define P_SETUP_FEATURES_SBUS2_OUT 2
  56. #define P_SETUP_FEATURES_PWM_RSSI 4
  57. #define P_SETUP_FEATURES_ADC_RSSI 8
  58. #define P_SETUP_FEATURES_ONESHOT 16
  59. #define P_SETUP_FEATURES_BRUSHED 32
  60. #define PAGE_REG_SETUP_ARMING 1
  61. #define P_SETUP_ARMING_IO_ARM_OK (1<<0)
  62. #define P_SETUP_ARMING_FMU_ARMED (1<<1)
  63. #define P_SETUP_ARMING_RC_HANDLING_DISABLED (1<<6)
  64. #define P_SETUP_ARMING_SAFETY_DISABLE_ON (1 << 11) // disable use of safety button for safety off->on
  65. #define P_SETUP_ARMING_SAFETY_DISABLE_OFF (1 << 12) // disable use of safety button for safety on->off
  66. #define PAGE_REG_SETUP_PWM_RATE_MASK 2
  67. #define PAGE_REG_SETUP_DEFAULTRATE 3
  68. #define PAGE_REG_SETUP_ALTRATE 4
  69. #define PAGE_REG_SETUP_REBOOT_BL 10
  70. #define PAGE_REG_SETUP_CRC 11
  71. #define PAGE_REG_SETUP_SBUS_RATE 19
  72. #define PAGE_REG_SETUP_IGNORE_SAFETY 20 /* bitmask of surfaces to ignore the safety status */
  73. #define PAGE_REG_SETUP_HEATER_DUTY_CYCLE 21
  74. #define PAGE_REG_SETUP_DSM_BIND 22
  75. // config page registers
  76. #define PAGE_CONFIG_PROTOCOL_VERSION 0
  77. #define PAGE_CONFIG_PROTOCOL_VERSION2 1
  78. #define IOMCU_PROTOCOL_VERSION 4
  79. #define IOMCU_PROTOCOL_VERSION2 10
  80. // magic value for rebooting to bootloader
  81. #define REBOOT_BL_MAGIC 14662
  82. #define PAGE_REG_SETUP_FORCE_SAFETY_OFF 12
  83. #define PAGE_REG_SETUP_FORCE_SAFETY_ON 14
  84. #define FORCE_SAFETY_MAGIC 22027
  85. struct page_config {
  86. uint16_t protocol_version;
  87. uint16_t protocol_version2;
  88. };
  89. struct page_reg_status {
  90. uint16_t freemem;
  91. uint32_t timestamp_ms;
  92. uint16_t vservo;
  93. uint16_t vrssi;
  94. uint32_t num_errors;
  95. uint32_t total_pkts;
  96. uint8_t flag_safety_off;
  97. uint8_t err_crc;
  98. uint8_t err_bad_opcode;
  99. uint8_t err_read;
  100. uint8_t err_write;
  101. uint8_t err_uart;
  102. };
  103. struct page_rc_input {
  104. uint8_t count;
  105. uint8_t flags_failsafe:1;
  106. uint8_t flags_rc_ok:1;
  107. uint8_t rc_protocol;
  108. uint16_t pwm[IOMCU_MAX_CHANNELS];
  109. };
  110. /*
  111. data for mixing on FMU failsafe
  112. */
  113. struct page_mixing {
  114. uint16_t servo_min[IOMCU_MAX_CHANNELS];
  115. uint16_t servo_max[IOMCU_MAX_CHANNELS];
  116. uint16_t servo_trim[IOMCU_MAX_CHANNELS];
  117. uint8_t servo_function[IOMCU_MAX_CHANNELS];
  118. uint8_t servo_reversed[IOMCU_MAX_CHANNELS];
  119. // RC input arrays are in AETR order
  120. uint16_t rc_min[4];
  121. uint16_t rc_max[4];
  122. uint16_t rc_trim[4];
  123. uint8_t rc_reversed[IOMCU_MAX_CHANNELS];
  124. uint8_t rc_channel[4];
  125. // gain for elevon and vtail mixing, x1000
  126. uint16_t mixing_gain;
  127. // channel which when high forces mixer
  128. int8_t rc_chan_override;
  129. // is the throttle an angle input?
  130. uint8_t throttle_is_angle;
  131. // mask of channels which are pure manual in override
  132. uint16_t manual_rc_mask;
  133. // enabled needs to be 1 to enable mixing
  134. uint8_t enabled;
  135. uint8_t pad; // pad to even size
  136. };