27 #if HAL_SUPPORT_RCOUT_SERIAL 39 void update_telemetry(
void);
40 bool process_input(uint8_t b);
47 AP_Int32 channel_mask;
81 enum motorPwmProtocol {
82 PWM_TYPE_STANDARD = 0,
95 FEATURE_RX_PPM = 1 << 0,
96 FEATURE_INFLIGHT_ACC_CAL = 1 << 2,
97 FEATURE_RX_SERIAL = 1 << 3,
98 FEATURE_MOTOR_STOP = 1 << 4,
99 FEATURE_SERVO_TILT = 1 << 5,
100 FEATURE_SOFTSERIAL = 1 << 6,
101 FEATURE_GPS = 1 << 7,
102 FEATURE_RANGEFINDER = 1 << 9,
103 FEATURE_TELEMETRY = 1 << 10,
104 FEATURE_3D = 1 << 12,
105 FEATURE_RX_PARALLEL_PWM = 1 << 13,
106 FEATURE_RX_MSP = 1 << 14,
107 FEATURE_RSSI_ADC = 1 << 15,
108 FEATURE_LED_STRIP = 1 << 16,
109 FEATURE_DASHBOARD = 1 << 17,
110 FEATURE_OSD = 1 << 18,
111 FEATURE_CHANNEL_FORWARDING = 1 << 20,
112 FEATURE_TRANSPONDER = 1 << 21,
113 FEATURE_AIRMODE = 1 << 22,
114 FEATURE_RX_SPI = 1 << 25,
115 FEATURE_SOFTSPI = 1 << 26,
116 FEATURE_ESC_SENSOR = 1 << 27,
117 FEATURE_ANTI_GRAVITY = 1 << 28,
118 FEATURE_DYNAMIC_FILTER = 1 << 29,
127 enum mspPacketType packetType;
133 enum escProtocol escMode;
141 BLHELI_HEADER_ADDR_LOW,
142 BLHELI_HEADER_ADDR_HIGH,
146 BLHELI_COMMAND_RECEIVED
153 enum blheliState
state;
158 uint8_t buf[256+3+8];
161 uint8_t interface_mode;
162 uint8_t deviceInfo[4];
171 static const uint8_t max_motors = 8;
178 uint32_t last_valid_ms;
181 uint32_t serial_start_ms;
184 bool motors_disabled;
190 uint8_t motor_map[max_motors];
193 uint32_t last_telem_request_us;
194 uint8_t last_telem_esc;
195 static const uint8_t telem_packet_size = 10;
197 bool msp_process_byte(uint8_t c);
198 void blheli_crc_update(uint8_t c);
199 bool blheli_4way_process_byte(uint8_t c);
200 void msp_send_reply(uint8_t cmd,
const uint8_t *buf, uint8_t len);
201 void putU16(uint8_t *b, uint16_t
v);
202 uint16_t getU16(
const uint8_t *b);
203 void putU32(uint8_t *b, uint32_t
v);
204 void putU16_BE(uint8_t *b, uint16_t
v);
205 void msp_process_command(
void);
206 void blheli_send_reply(
const uint8_t *buf, uint16_t len);
207 uint16_t BL_CRC(
const uint8_t *buf, uint16_t len);
209 void setDisconnected(
void);
210 bool BL_SendBuf(
const uint8_t *buf, uint16_t len);
211 bool BL_ReadBuf(uint8_t *buf, uint16_t len);
212 uint8_t BL_GetACK(uint16_t timeout_ms=2);
213 bool BL_SendCMDSetAddress();
214 bool BL_ReadA(uint8_t cmd, uint8_t *buf, uint16_t n);
219 uint8_t BL_SendCMDSetBuffer(
const uint8_t *buf, uint16_t nbytes);
220 bool BL_WriteA(uint8_t cmd,
const uint8_t *buf, uint16_t nbytes, uint32_t timeout);
223 void blheli_process_command(
void);
224 void run_connection_test(uint8_t
chan);
225 uint8_t telem_crc8(uint8_t crc, uint8_t crc_seed)
const;
226 void read_telemetry_packet(
void);
235 #define UDID_START 0x1FFF7A10 238 #endif // HAL_SUPPORT_RCOUT_SERIAL uint8_t BL_VerifyFlash(ioMem_t *pMem)
void BL_SendCMDRunRestartBootloader(uint8_32_u *pDeviceInfo)
bool isMcuConnected(void)
uint8_t BL_SendCMDKeepAlive(void)
A system for managing and storing variables that are of general interest to the system.
uint8_t BL_PageErase(ioMem_t *pMem)
Common definitions and utility routines for the ArduPilot libraries.
AP_HAL::AnalogSource * chan
uint8_t BL_WriteFlash(ioMem_t *pMem)
uint8_t BL_ConnectEx(uint8_32_u *pDeviceInfo)