Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_BLHeli/AP_BLHeli.h
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15implementation of MSP and BLHeli-4way protocols for pass-through ESC16calibration and firmware update1718With thanks to betaflight for a great reference implementation19*/2021#pragma once2223#include <AP_Common/AP_Common.h>24#include <AP_HAL/AP_HAL.h>2526#define HAVE_AP_BLHELI_SUPPORT HAL_SUPPORT_RCOUT_SERIAL2728#if HAL_SUPPORT_RCOUT_SERIAL2930#include <AP_ESC_Telem/AP_ESC_Telem_Backend.h>3132#include <AP_Param/AP_Param.h>33#include <Filter/LowPassFilter.h>34#include <AP_MSP/msp_protocol.h>35#include "blheli_4way_protocol.h"3637#define AP_BLHELI_MAX_ESCS 83839class AP_BLHeli : public AP_ESC_Telem_Backend {4041public:42AP_BLHeli();4344void update(void);45void init(uint32_t motor_mask, AP_HAL::RCOutput::output_mode mode);46void update_telemetry(void);47bool process_input(uint8_t b);4849static const struct AP_Param::GroupInfo var_info[];5051bool has_bidir_dshot(uint8_t esc_index) const {52return channel_bidir_dshot_mask.get() & (1U << motor_map[esc_index]);53}5455uint32_t get_bidir_dshot_mask() const { return channel_bidir_dshot_mask.get(); }56uint8_t get_motor_poles() const { return motor_poles.get(); }57uint16_t get_telemetry_rate() const { return telem_rate.get(); }5859static AP_BLHeli *get_singleton(void) {60return _singleton;61}6263private:64static AP_BLHeli *_singleton;6566// mask of channels to use for BLHeli protocol67AP_Int32 channel_mask;68AP_Int32 channel_reversible_mask;69AP_Int32 channel_reversed_mask;70AP_Int8 channel_auto;71AP_Int8 run_test;72AP_Int16 timeout_sec;73AP_Int16 telem_rate;74AP_Int8 debug_level;75AP_Int8 output_type;76AP_Int8 control_port;77AP_Int8 motor_poles;78// mask of channels with bi-directional dshot enabled79AP_Int32 channel_bidir_dshot_mask;8081enum mspState {82MSP_IDLE=0,83MSP_HEADER_START,84MSP_HEADER_M,85MSP_HEADER_ARROW,86MSP_HEADER_SIZE,87MSP_HEADER_CMD,88MSP_COMMAND_RECEIVED89};9091enum mspPacketType {92MSP_PACKET_COMMAND,93MSP_PACKET_REPLY94};9596enum escProtocol {97PROTOCOL_SIMONK = 0,98PROTOCOL_BLHELI = 1,99PROTOCOL_KISS = 2,100PROTOCOL_KISSALL = 3,101PROTOCOL_CASTLE = 4,102PROTOCOL_MAX = 5,103PROTOCOL_NONE = 0xfe,104PROTOCOL_4WAY = 0xff105};106107enum motorPwmProtocol {108PWM_TYPE_STANDARD = 0,109PWM_TYPE_ONESHOT125,110PWM_TYPE_ONESHOT42,111PWM_TYPE_MULTISHOT,112PWM_TYPE_BRUSHED,113PWM_TYPE_DSHOT150,114PWM_TYPE_DSHOT300,115PWM_TYPE_DSHOT600,116PWM_TYPE_DSHOT1200,117PWM_TYPE_PROSHOT1000,118};119120enum MSPFeatures {121FEATURE_RX_PPM = 1 << 0,122FEATURE_INFLIGHT_ACC_CAL = 1 << 2,123FEATURE_RX_SERIAL = 1 << 3,124FEATURE_MOTOR_STOP = 1 << 4,125FEATURE_SERVO_TILT = 1 << 5,126FEATURE_SOFTSERIAL = 1 << 6,127FEATURE_GPS = 1 << 7,128FEATURE_RANGEFINDER = 1 << 9,129FEATURE_TELEMETRY = 1 << 10,130FEATURE_3D = 1 << 12,131FEATURE_RX_PARALLEL_PWM = 1 << 13,132FEATURE_RX_MSP = 1 << 14,133FEATURE_RSSI_ADC = 1 << 15,134FEATURE_LED_STRIP = 1 << 16,135FEATURE_DASHBOARD = 1 << 17,136FEATURE_OSD = 1 << 18,137FEATURE_CHANNEL_FORWARDING = 1 << 20,138FEATURE_TRANSPONDER = 1 << 21,139FEATURE_AIRMODE = 1 << 22,140FEATURE_RX_SPI = 1 << 25,141FEATURE_SOFTSPI = 1 << 26,142FEATURE_ESC_SENSOR = 1 << 27,143FEATURE_ANTI_GRAVITY = 1 << 28,144FEATURE_DYNAMIC_FILTER = 1 << 29,145};146147148/*149state of MSP command processing150*/151struct {152enum mspState state;153enum mspPacketType packetType;154uint8_t offset;155uint8_t dataSize;156uint8_t checksum;157uint8_t buf[192];158uint8_t cmdMSP;159enum escProtocol escMode;160uint8_t portIndex;161} msp;162163enum blheliState {164BLHELI_IDLE=0,165BLHELI_HEADER_START,166BLHELI_HEADER_CMD,167BLHELI_HEADER_ADDR_LOW,168BLHELI_HEADER_ADDR_HIGH,169BLHELI_HEADER_LEN,170BLHELI_CRC1,171BLHELI_CRC2,172BLHELI_COMMAND_RECEIVED173};174175/*176state of blheli 4way protocol handling177*/178struct {179enum blheliState state;180uint8_t command;181uint16_t address;182uint16_t param_len;183uint16_t offset;184uint8_t buf[256+3+8];185uint8_t crc1;186uint16_t crc;187bool connected[AP_BLHELI_MAX_ESCS];188uint8_t interface_mode[AP_BLHELI_MAX_ESCS];189uint8_t deviceInfo[AP_BLHELI_MAX_ESCS][4];190uint8_t chan;191uint8_t ack;192} blheli;193194const uint16_t esc_status_addr = 0xEB00;195196// protocol reported by ESC in esc_status197enum esc_protocol {198ESC_PROTOCOL_NONE=0,199ESC_PROTOCOL_NORMAL=1,200ESC_PROTOCOL_ONESHOT125=2,201ESC_PROTOCOL_DSHOT=5,202};203204// ESC status structure at address 0xEB00205struct PACKED esc_status {206uint8_t unknown[3];207enum esc_protocol protocol;208uint32_t good_frames;209uint32_t bad_frames;210uint32_t unknown2;211};212213214AP_HAL::UARTDriver *uart;215AP_HAL::UARTDriver *debug_uart;216AP_HAL::UARTDriver *telem_uart;217218static const uint8_t max_motors = AP_BLHELI_MAX_ESCS;219uint8_t num_motors;220221// last log output to avoid beat frequencies222uint32_t last_log_ms[max_motors];223224// have we initialised the interface?225bool initialised;226227// last valid packet timestamp228uint32_t last_valid_ms;229230// when did we start the serial ESC output?231uint32_t serial_start_ms;232233// have we disabled motor outputs?234bool motors_disabled;235// mask of channels that should normally be disabled236uint32_t motors_disabled_mask;237238// have we locked the UART?239bool uart_locked;240241// true if we have a mix of reversible and normal ESC242bool mixed_type;243244// mapping from BLHeli motor numbers to RC output channels245uint8_t motor_map[max_motors];246uint32_t motor_mask;247248// convert between servo number and FMU channel number for ESC telemetry249uint8_t chan_offset;250251// when did we last request telemetry?252uint32_t last_telem_request_us;253uint8_t last_telem_esc;254static const uint8_t telem_packet_size = 10;255bool telem_uart_started;256uint32_t last_telem_byte_read_us;257int8_t last_control_port;258259bool msp_process_byte(uint8_t c);260void blheli_crc_update(uint8_t c);261bool blheli_4way_process_byte(uint8_t c);262void msp_send_ack(uint8_t cmd);263void msp_send_reply(uint8_t cmd, const uint8_t *buf, uint8_t len);264void putU16(uint8_t *b, uint16_t v);265uint16_t getU16(const uint8_t *b);266void putU32(uint8_t *b, uint32_t v);267void putU16_BE(uint8_t *b, uint16_t v);268void msp_process_command(void);269void blheli_send_reply(const uint8_t *buf, uint16_t len);270uint16_t BL_CRC(const uint8_t *buf, uint16_t len);271bool isMcuConnected(void);272void setDisconnected(void);273bool BL_SendBuf(const uint8_t *buf, uint16_t len);274bool BL_ReadBuf(uint8_t *buf, uint16_t len);275uint8_t BL_GetACK(uint16_t timeout_ms=2);276bool BL_SendCMDSetAddress();277bool BL_ReadA(uint8_t cmd, uint8_t *buf, uint16_t n);278bool BL_ConnectEx(void);279bool BL_SendCMDKeepAlive(void);280bool BL_PageErase(void);281void BL_SendCMDRunRestartBootloader(void);282uint8_t BL_SendCMDSetBuffer(const uint8_t *buf, uint16_t nbytes);283bool BL_WriteA(uint8_t cmd, const uint8_t *buf, uint16_t nbytes, uint32_t timeout);284uint8_t BL_WriteFlash(const uint8_t *buf, uint16_t n);285bool BL_VerifyFlash(const uint8_t *buf, uint16_t n);286void blheli_process_command(void);287void run_connection_test(uint8_t chan);288void read_telemetry_packet(void);289void log_bidir_telemetry(void);290291// protocol handler hook292bool protocol_handler(uint8_t , AP_HAL::UARTDriver *);293};294295#endif // HAL_SUPPORT_RCOUT_SERIAL296297298