6 #include <GCS_MAVLink/include/mavlink/v2.0/checksum.h> 10 #define NUM_CHANNELS 4 11 #define ESC_MAGIC 0xF7 18 void setup()
override;
39 int16_t c = hal.UART->read();
76 if (crc2 != u2.crc16) {
77 hal.
console->
printf(
"bad CRC 0x%04x should be 0x%04x\n", (
unsigned)crc2, (
unsigned)u2.crc16);
83 if (u.period[i] == 0) {
100 (
unsigned)u.period[0],
101 (
unsigned)u.period[1],
102 (
unsigned)u.period[2],
103 (
unsigned)u.period[3]);
109 uint8_t magic = 0xf6;
114 rcin.crc = crc_calculate((uint8_t*)&rcin.rcin[0], 16);
115 hal.UART->write((uint8_t*)&rcin,
sizeof(rcin));
virtual void force_safety_off(void)
AP_HAL::UARTDriver * console
virtual void set_freq(uint32_t chmask, uint16_t freq_hz)=0
#define AP_HAL_MAIN_CALLBACKS(CALLBACKS)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
virtual void delay(uint16_t ms)=0
virtual void enable_ch(uint8_t ch)=0
virtual void printf(const char *,...) FMT_PRINTF(2
virtual void write(uint8_t ch, uint16_t period_us)=0
virtual void delay_microseconds(uint16_t us)=0
AP_HAL::Scheduler * scheduler