Path: blob/master/libraries/AP_BLHeli/AP_BLHeli.cpp
9451 views
/*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 reference19implementation. Several of the functions below are based on20betaflight equivalent functions21*/2223#include "AP_BLHeli.h"2425#if HAVE_AP_BLHELI_SUPPORT2627#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS28#include <hal.h>29#endif3031#include <AP_Math/crc.h>32#include <AP_Vehicle/AP_Vehicle_Type.h>33#if APM_BUILD_TYPE(APM_BUILD_Rover)34#include <AR_Motors/AP_MotorsUGV.h>35#else36#include <AP_Motors/AP_Motors_Class.h>37#endif38#include <GCS_MAVLink/GCS_MAVLink.h>39#include <GCS_MAVLink/GCS.h>40#include <AP_SerialManager/AP_SerialManager.h>41#include <AP_BoardConfig/AP_BoardConfig.h>42#include <AP_ESC_Telem/AP_ESC_Telem.h>43#include <SRV_Channel/SRV_Channel.h>44#include <AP_BattMonitor/AP_BattMonitor.h>4546extern const AP_HAL::HAL& hal;4748#define debug(fmt, args ...) do { if (debug_level) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ESC: " fmt, ## args); } } while (0)49#ifdef BLHELI_DEBUG50#define debug_console(fmt, args ...) do { hal.console->printf(fmt "\n", ## args); } while (0)51#else52#define debug_console(fmt, args ...) do {} while(0)53#endif5455// key for locking UART for exclusive use. This prevents any other writes from corrupting56// the MSP protocol on hal.console57#define BLHELI_UART_LOCK_KEY 0x201804025859// if no packets are received for this time and motor control is active BLH will disconnect (stoping motors)60#define MOTOR_ACTIVE_TIMEOUT 10006162const AP_Param::GroupInfo AP_BLHeli::var_info[] = {63// @Param: MASK64// @DisplayName: BLHeli Channel Bitmask65// @Description: Enable of BLHeli pass-thru servo protocol support to specific channels. This mask is in addition to motors enabled using SERVO_BLH_AUTO (if any)66// @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16, 16:Channel 17, 17: Channel 18, 18: Channel 19, 19: Channel 20, 20: Channel 21, 21: Channel 22, 22: Channel 23, 23: Channel 24, 24: Channel 25, 25: Channel 26, 26: Channel 27, 27: Channel 28, 28: Channel 29, 29: Channel 30, 30: Channel 31, 31: Channel 3267// @User: Advanced68// @RebootRequired: True69AP_GROUPINFO("MASK", 1, AP_BLHeli, channel_mask, 0),7071#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_Rover)72// @Param: AUTO73// @DisplayName: BLHeli pass-thru auto-enable for multicopter motors74// @Description: If set to 1 this auto-enables BLHeli pass-thru support for all multicopter motors75// @Values: 0:Disabled,1:Enabled76// @User: Standard77// @RebootRequired: True78AP_GROUPINFO("AUTO", 2, AP_BLHeli, channel_auto, 0),79#endif8081// @Param: TEST82// @DisplayName: BLHeli internal interface test83// @Description: Setting SERVO_BLH_TEST to a motor number enables an internal test of the BLHeli ESC protocol to the corresponding ESC. The debug output is displayed on the USB console.84// @Values: 0:Disabled,1:TestMotor1,2:TestMotor2,3:TestMotor3,4:TestMotor4,5:TestMotor5,6:TestMotor6,7:TestMotor7,8:TestMotor885// @User: Advanced86AP_GROUPINFO("TEST", 3, AP_BLHeli, run_test, 0),8788// @Param: TMOUT89// @DisplayName: BLHeli protocol timeout90// @Description: This sets the inactivity timeout for the BLHeli protocol in seconds. If no packets are received in this time normal MAVLink operations are resumed. A value of 0 means no timeout91// @Units: s92// @Range: 0 30093// @User: Standard94AP_GROUPINFO("TMOUT", 4, AP_BLHeli, timeout_sec, 0),9596// @Param: TRATE97// @DisplayName: BLHeli telemetry rate98// @Description: This sets the rate in Hz for requesting telemetry from ESCs. It is the rate per ESC. Setting to zero disables telemetry requests99// @Units: Hz100// @Range: 0 500101// @User: Standard102AP_GROUPINFO("TRATE", 5, AP_BLHeli, telem_rate, 10),103104// @Param: DEBUG105// @DisplayName: BLHeli debug level106// @Description: When set to 1 this enabled verbose debugging output over MAVLink when the blheli protocol is active. This can be used to diagnose failures.107// @Values: 0:Disabled,1:Enabled108// @User: Standard109AP_GROUPINFO("DEBUG", 6, AP_BLHeli, debug_level, 0),110111// @Param: OTYPE112// @DisplayName: BLHeli output type override113// @Description: When set to a non-zero value this overrides the output type for the output channels given by SERVO_BLH_MASK. This can be used to enable DShot on outputs that are not part of the multicopter motors group.114// @Values: 0:None,1:OneShot,2:OneShot125,3:Brushed,4:DShot150,5:DShot300,6:DShot600,7:DShot1200115// @User: Advanced116// @RebootRequired: True117AP_GROUPINFO("OTYPE", 7, AP_BLHeli, output_type, 0),118119// @Param: PORT120// @DisplayName: Control port121// @Description: This sets the mavlink channel to use for blheli pass-thru. The channel number is determined by the number of serial ports configured to use mavlink. So 0 is always the console, 1 is the next serial port using mavlink, 2 the next after that and so on.122// @Values: 0:Console,1:Mavlink Serial Channel1,2:Mavlink Serial Channel2,3:Mavlink Serial Channel3,4:Mavlink Serial Channel4,5:Mavlink Serial Channel5123// @User: Advanced124AP_GROUPINFO("PORT", 8, AP_BLHeli, control_port, 0),125126// @Param: POLES127// @DisplayName: BLHeli Motor Poles128// @Description: This allows calculation of true RPM from ESC's eRPM. The default is 14.129// @Range: 1 127130// @User: Advanced131// @RebootRequired: True132AP_GROUPINFO("POLES", 9, AP_BLHeli, motor_poles, 14),133134// @Param: 3DMASK135// @DisplayName: BLHeli bitmask of 3D channels136// @Description: Mask of channels which are dynamically reversible. This is used to configure ESCs in '3D' mode, allowing for the motor to spin in either direction. Note that setting an ESC as reversible with this option on AM32 will result in the forward direction of the ESC changing. You can combine with parameter with the SERVO_BLH_RVMASK parameter to maintain the same direction when the ESC is in 3D mode as it has in unidirectional (non-3D) mode.137// @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16, 16:Channel 17, 17: Channel 18, 18: Channel 19, 19: Channel 20, 20: Channel 21, 21: Channel 22, 22: Channel 23, 23: Channel 24, 24: Channel 25, 25: Channel 26, 26: Channel 27, 27: Channel 28, 28: Channel 29, 29: Channel 30, 30: Channel 31, 31: Channel 32138// @User: Advanced139// @RebootRequired: True140AP_GROUPINFO("3DMASK", 10, AP_BLHeli, channel_reversible_mask, 0),141142#if defined(HAL_WITH_BIDIR_DSHOT) || HAL_WITH_IO_MCU_BIDIR_DSHOT143// @Param: BDMASK144// @DisplayName: BLHeli bitmask of bi-directional dshot channels145// @Description: Mask of channels which support bi-directional dshot telemetry. This is used for ESCs which have firmware that supports bi-directional dshot allowing fast rpm telemetry values to be returned for the harmonic notch.146// @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16, 16:Channel 17, 17: Channel 18, 18: Channel 19, 19: Channel 20, 20: Channel 21, 21: Channel 22, 22: Channel 23, 23: Channel 24, 24: Channel 25, 25: Channel 26, 26: Channel 27, 27: Channel 28, 28: Channel 29, 29: Channel 30, 30: Channel 31, 31: Channel 32147// @User: Advanced148// @RebootRequired: True149AP_GROUPINFO("BDMASK", 11, AP_BLHeli, channel_bidir_dshot_mask, 0),150#endif151152// @Param: RVMASK153// @DisplayName: BLHeli bitmask of reversed channels154// @Description: Mask of channels which are reversed. This is used to configure ESCs to reverse motor direction. Note that when combined with SERVO_BLH_3DMASK this will change what direction is considered to be forward.155// @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16, 16:Channel 17, 17: Channel 18, 18: Channel 19, 19: Channel 20, 20: Channel 21, 21: Channel 22, 22: Channel 23, 23: Channel 24, 24: Channel 25, 25: Channel 26, 26: Channel 27, 27: Channel 28, 28: Channel 29, 29: Channel 30, 30: Channel 31, 31: Channel 32156// @User: Advanced157// @RebootRequired: True158AP_GROUPINFO("RVMASK", 12, AP_BLHeli, channel_reversed_mask, 0),159160AP_GROUPEND161};162163#define RPM_SLEW_RATE 50164165AP_BLHeli *AP_BLHeli::_singleton;166167// constructor168AP_BLHeli::AP_BLHeli(void)169{170// set defaults from the parameter table171AP_Param::setup_object_defaults(this, var_info);172_singleton = this;173last_control_port = -1;174}175176// map an incoming BLHeli motor request to the appropriate177// output channel for use in serial output so that motor numbers178// are observed179uint8_t AP_BLHeli::blheli_chan_to_output_chan(uint8_t motor)180{181// user has overidden the default output mask, we must use the motor map182if (channel_mask.get() != 0) {183return motor_map[motor];184}185// user is using motor mask and so we can use the servo channel options186uint8_t chan = 0; // 0 means motor 1 and is ok as a fallback187SRV_Channels::find_channel(SRV_Channels::get_motor_function(motor), chan);188return chan;189}190191/*192process one byte of serial input for MSP protocol193*/194bool AP_BLHeli::msp_process_byte(uint8_t c)195{196if (msp.state == MSP_IDLE) {197msp.escMode = PROTOCOL_NONE;198if (c == '$') {199msp.state = MSP_HEADER_START;200} else {201return false;202}203} else if (msp.state == MSP_HEADER_START) {204msp.state = (c == 'M') ? MSP_HEADER_M : MSP_IDLE;205} else if (msp.state == MSP_HEADER_M) {206msp.state = MSP_IDLE;207switch (c) {208case '<': // COMMAND209msp.packetType = MSP_PACKET_COMMAND;210msp.state = MSP_HEADER_ARROW;211break;212case '>': // REPLY213msp.packetType = MSP_PACKET_REPLY;214msp.state = MSP_HEADER_ARROW;215break;216default:217break;218}219} else if (msp.state == MSP_HEADER_ARROW) {220if (c > sizeof(msp.buf)) {221msp.state = MSP_IDLE;222} else {223msp.dataSize = c;224msp.offset = 0;225msp.checksum = 0;226msp.checksum ^= c;227msp.state = MSP_HEADER_SIZE;228}229} else if (msp.state == MSP_HEADER_SIZE) {230msp.cmdMSP = c;231msp.checksum ^= c;232msp.state = MSP_HEADER_CMD;233} else if (msp.state == MSP_HEADER_CMD && msp.offset < msp.dataSize) {234msp.checksum ^= c;235msp.buf[msp.offset++] = c;236} else if (msp.state == MSP_HEADER_CMD && msp.offset >= msp.dataSize) {237if (msp.checksum == c) {238msp.state = MSP_COMMAND_RECEIVED;239} else {240msp.state = MSP_IDLE;241}242}243return true;244}245246/*247update CRC state for blheli protocol248*/249void AP_BLHeli::blheli_crc_update(uint8_t c)250{251blheli.crc = crc_xmodem_update(blheli.crc, c);252}253254/*255process one byte of serial input for blheli 4way protocol256*/257bool AP_BLHeli::blheli_4way_process_byte(uint8_t c)258{259if (blheli.state == BLHELI_IDLE) {260if (c == cmd_Local_Escape) {261blheli.state = BLHELI_HEADER_START;262blheli.crc = 0;263blheli_crc_update(c);264} else {265return false;266}267} else if (blheli.state == BLHELI_HEADER_START) {268blheli.command = c;269blheli_crc_update(c);270blheli.state = BLHELI_HEADER_CMD;271} else if (blheli.state == BLHELI_HEADER_CMD) {272blheli.address = c<<8;273blheli.state = BLHELI_HEADER_ADDR_HIGH;274blheli_crc_update(c);275} else if (blheli.state == BLHELI_HEADER_ADDR_HIGH) {276blheli.address |= c;277blheli.state = BLHELI_HEADER_ADDR_LOW;278blheli_crc_update(c);279} else if (blheli.state == BLHELI_HEADER_ADDR_LOW) {280blheli.state = BLHELI_HEADER_LEN;281blheli.param_len = c?c:256;282blheli.offset = 0;283blheli_crc_update(c);284} else if (blheli.state == BLHELI_HEADER_LEN) {285blheli.buf[blheli.offset++] = c;286blheli_crc_update(c);287if (blheli.offset == blheli.param_len) {288blheli.state = BLHELI_CRC1;289}290} else if (blheli.state == BLHELI_CRC1) {291blheli.crc1 = c;292blheli.state = BLHELI_CRC2;293} else if (blheli.state == BLHELI_CRC2) {294uint16_t crc = blheli.crc1<<8 | c;295if (crc == blheli.crc) {296blheli.state = BLHELI_COMMAND_RECEIVED;297} else {298blheli.state = BLHELI_IDLE;299}300}301return true;302}303304305/*306send a MSP protocol ack307*/308void AP_BLHeli::msp_send_ack(uint8_t cmd)309{310msp_send_reply(cmd, 0, 0);311}312313/*314send a MSP protocol reply315*/316void AP_BLHeli::msp_send_reply(uint8_t cmd, const uint8_t *buf, uint8_t len)317{318uint8_t *b = &msp.buf[0];319*b++ = '$';320*b++ = 'M';321*b++ = '>';322*b++ = len;323*b++ = cmd;324// acks do not have a payload325if (len > 0) {326memcpy(b, buf, len);327}328b += len;329uint8_t c = 0;330for (uint8_t i=0; i<len+2; i++) {331c ^= msp.buf[i+3];332}333*b++ = c;334uart->write_locked(&msp.buf[0], len+6, BLHELI_UART_LOCK_KEY);335}336337void AP_BLHeli::putU16(uint8_t *b, uint16_t v)338{339b[0] = v;340b[1] = v >> 8;341}342343uint16_t AP_BLHeli::getU16(const uint8_t *b)344{345return b[0] | (b[1]<<8);346}347348void AP_BLHeli::putU32(uint8_t *b, uint32_t v)349{350b[0] = v;351b[1] = v >> 8;352b[2] = v >> 16;353b[3] = v >> 24;354}355356void AP_BLHeli::putU16_BE(uint8_t *b, uint16_t v)357{358b[0] = v >> 8;359b[1] = v;360}361362/*363process a MSP command from GCS364*/365void AP_BLHeli::msp_process_command(void)366{367debug("MSP cmd %u len=%u", msp.cmdMSP, msp.dataSize);368switch (msp.cmdMSP) {369case MSP_API_VERSION: {370debug("MSP_API_VERSION");371uint8_t buf[3] = { MSP_PROTOCOL_VERSION, API_VERSION_MAJOR, API_VERSION_MINOR };372msp_send_reply(msp.cmdMSP, buf, sizeof(buf));373break;374}375376case MSP_FC_VARIANT:377debug("MSP_FC_VARIANT");378msp_send_reply(msp.cmdMSP, (const uint8_t *)ARDUPILOT_IDENTIFIER, FLIGHT_CONTROLLER_IDENTIFIER_LENGTH);379break;380381/*382Notes:383version 3.3.1 adds a reply to MSP_SET_MOTOR which was missing384version 3.3.0 requires a workaround in blheli suite to handle MSP_SET_MOTOR without an ack385*/386case MSP_FC_VERSION: {387debug("MSP_FC_VERSION");388uint8_t version[3] = { 3, 3, 1 };389msp_send_reply(msp.cmdMSP, version, sizeof(version));390break;391}392case MSP_BOARD_INFO: {393debug("MSP_BOARD_INFO");394// send a generic 'ArduPilot ChibiOS' board type395uint8_t buf[7] = { 'A', 'R', 'C', 'H', 0, 0, 0 };396msp_send_reply(msp.cmdMSP, buf, sizeof(buf));397break;398}399400case MSP_BUILD_INFO: {401debug("MSP_BUILD_INFO");402// build date, build time, git version403uint8_t buf[26] {4040x4d, 0x61, 0x72, 0x20, 0x31, 0x36, 0x20, 0x32, 0x30,4050x31, 0x38, 0x30, 0x38, 0x3A, 0x34, 0x32, 0x3a, 0x32, 0x39,4060x62, 0x30, 0x66, 0x66, 0x39, 0x32, 0x38};407msp_send_reply(msp.cmdMSP, buf, sizeof(buf));408break;409}410411case MSP_REBOOT:412debug("MSP: ignoring reboot command, end serial comms");413serial_end();414blheli.connected[blheli.chan] = false;415break;416417case MSP_UID:418// MCU identifier419debug("MSP_UID");420msp_send_reply(msp.cmdMSP, (const uint8_t *)UDID_START, 12);421break;422423// a literal "4" is used for the PWMType here to allow Rover424// to use the same number for the same protocol. At time of425// writing the AP_MotorsUGV::PWMType has not been unified with426// AP_Motors::PWMType.427case MSP_ADVANCED_CONFIG: {428debug("MSP_ADVANCED_CONFIG");429uint8_t buf[10];430buf[0] = 1; // gyro sync denom431buf[1] = 4; // pid process denom432buf[2] = 0; // use unsynced pwm433buf[3] = 4; // (uint8_t)AP_Motors::PWMType::DSHOT150;434putU16(&buf[4], 480); // motor PWM Rate435putU16(&buf[6], 450); // idle offset value436buf[8] = 0; // use 32kHz437buf[9] = 0; // motor PWM inversion438msp_send_reply(msp.cmdMSP, buf, sizeof(buf));439break;440}441442case MSP_FEATURE_CONFIG: {443debug("MSP_FEATURE_CONFIG");444uint8_t buf[4];445putU32(buf, (channel_reversible_mask.get() != 0) ? FEATURE_3D : 0); // from MSPFeatures enum446msp_send_reply(msp.cmdMSP, buf, sizeof(buf));447break;448}449450case MSP_STATUS: {451debug("MSP_STATUS");452uint8_t buf[21];453putU16(&buf[0], 1000); // loop time usec454putU16(&buf[2], 0); // i2c error count455putU16(&buf[4], 0x27); // available sensors456putU32(&buf[6], 0); // flight modes457buf[10] = 0; // pid profile index458putU16(&buf[11], 5); // system load percent459putU16(&buf[13], 0); // gyro cycle time460buf[15] = 0; // flight mode flags length461buf[16] = 18; // arming disable flags count462putU32(&buf[17], 0); // arming disable flags463msp_send_reply(msp.cmdMSP, buf, sizeof(buf));464break;465}466467case MSP_MOTOR_3D_CONFIG: {468debug("MSP_MOTOR_3D_CONFIG");469uint8_t buf[6];470putU16(&buf[0], 1406); // 3D deadband low471putU16(&buf[2], 1514); // 3D deadband high472putU16(&buf[4], 1460); // 3D neutral473msp_send_reply(msp.cmdMSP, buf, sizeof(buf));474break;475}476477case MSP_BATTERY_STATE: {478debug("MSP_BATTERY_STATE");479// ESC configurator seems to care a lot about the battery state,480// try and at least provide something believable481uint8_t buf[11] {};482#if AP_BATTERY_ENABLED483AP_BattMonitor &battery = AP::battery();484float v;485#if HAL_WITH_ESC_TELEM486if (!AP::esc_telem().get_voltage(blheli_chan_to_output_chan(blheli.chan), v)) {487v = battery.voltage();488}489#else490v = battery.voltage();491#endif492buf[0] = battery.healthy() ? uint8_t(roundf(v / 3.85)) : 0; // cell count, 0 means no battery493putU16(&buf[1], uint16_t(battery.pack_capacity_mah())); // capacity in mAh494buf[3] = uint8_t(roundf(v * 10.0)); // legacy V in 0.1V steps495496float cons = 0;497UNUSED_RESULT(battery.consumed_mah(cons));498putU16(&buf[4], uint16_t(roundf(cons))); // mAh used499500float amps = 0.0;501UNUSED_RESULT(battery.current_amps(amps));502putU16(&buf[6], uint16_t(roundf(amps * 100.0))); // A in 0.01A steps503buf[8] = battery.healthy(); // alerts/state504// We are advertising MSP v1.42 which means supporting the new voltage field505putU16(&buf[9], uint16_t(roundf(v * 100.0))); // Voltage in 0.01V steps506#endif507msp_send_reply(msp.cmdMSP, buf, sizeof(buf));508break;509}510511case MSP_MOTOR_CONFIG: {512debug("MSP_MOTOR_CONFIG(n=%u, p=%u)", num_motors, motor_poles.get());513uint8_t buf[10];514SRV_Channel* channel = SRV_Channels::srv_channel(blheli_chan_to_output_chan(0));515putU16(&buf[0], channel->get_output_min()); // min throttle516putU16(&buf[2], channel->get_output_max()); // max throttle517putU16(&buf[4], channel->get_output_min()); // min command518// API 1.42519buf[6] = num_motors; // motorCount520buf[7] = motor_poles; // motorPoleCount521buf[8] = 0; // useDshotTelemetry522buf[9] = 0; // FEATURE_ESC_SENSOR523msp_send_reply(msp.cmdMSP, buf, sizeof(buf));524break;525}526527case MSP_MOTOR: {528debug("MSP_MOTOR");529// get the output going to each motor530uint8_t buf[16] {};531for (uint8_t i = 0; i < num_motors; i++) {532// if we have a mix of reversible and normal report a PWM of zero, this allows BLHeliSuite to conect533uint8_t chan = blheli_chan_to_output_chan(i);534uint16_t v = mixed_type ? 0 : hal.rcout->read(blheli_chan_to_output_chan(i));535putU16(&buf[2*i], v);536debug("MOTOR %u chan: %u val: %u",i,chan,v);537}538msp_send_reply(msp.cmdMSP, buf, sizeof(buf));539break;540}541542case MSP_SET_MOTOR: {543debug("MSP_SET_MOTOR");544if (!mixed_type) {545// set the output to each motor546uint8_t nmotors = msp.dataSize / 2;547debug("MSP_SET_MOTOR %u", nmotors);548motors_disabled_mask = SRV_Channels::get_disabled_channel_mask();549SRV_Channels::set_disabled_channel_mask(0xFFFF);550motors_disabled = true;551EXPECT_DELAY_MS(1000);552hal.rcout->cork();553for (uint8_t i = 0; i < nmotors; i++) {554if (i >= num_motors) {555break;556}557uint16_t v = getU16(&msp.buf[i*2]);558debug("MSP_SET_MOTOR %u %u", i, v);559// map from a MSP value to a value in the range 1000 to 2000560uint16_t pwm = (v < 1000)?0:v;561hal.rcout->write(blheli_chan_to_output_chan(i), pwm);562}563hal.rcout->push();564} else {565debug("mixed type, Motors Disabled");566}567msp_send_ack(msp.cmdMSP);568break;569}570571case MSP_SET_PASSTHROUGH: {572debug("MSP_SET_PASSTHROUGH");573if (msp.dataSize == 0) {574msp.escMode = PROTOCOL_4WAY;575} else if (msp.dataSize == 2) {576msp.escMode = (enum escProtocol)msp.buf[0];577msp.portIndex = msp.buf[1];578}579debug("escMode=%u portIndex=%u num_motors=%u", msp.escMode, msp.portIndex, num_motors);580uint8_t n = num_motors;581switch (msp.escMode) {582case PROTOCOL_4WAY:583break;584default:585n = 0;586serial_end();587break;588}589// doing the serial setup here avoids delays when doing it on demand and makes590// BLHeliSuite considerably more reliable591EXPECT_DELAY_MS(1000);592if (!hal.rcout->serial_setup_output(blheli_chan_to_output_chan(0), 19200, motor_mask)) {593msp_send_ack(ACK_D_GENERAL_ERROR);594break;595} else {596msp_send_reply(msp.cmdMSP, &n, 1);597}598break;599}600default:601debug("Unknown MSP command %u", msp.cmdMSP);602break;603}604}605606/*607send a blheli 4way protocol reply608*/609void AP_BLHeli::blheli_send_reply(const uint8_t *buf, uint16_t len)610{611uint8_t *b = &blheli.buf[0];612*b++ = cmd_Remote_Escape;613*b++ = blheli.command;614putU16_BE(b, blheli.address); b += 2;615*b++ = len==256?0:len;616memcpy(b, buf, len);617b += len;618*b++ = blheli.ack;619putU16_BE(b, crc_xmodem(&blheli.buf[0], len+6));620uart->write_locked(&blheli.buf[0], len+8, BLHELI_UART_LOCK_KEY);621debug("OutB(%u) 0x%02x ack=0x%02x", len+8, (unsigned)blheli.command, blheli.ack);622}623624/*625CRC used when talking to ESCs626*/627uint16_t AP_BLHeli::BL_CRC(const uint8_t *buf, uint16_t len)628{629uint16_t crc = 0;630while (len--) {631uint8_t xb = *buf++;632for (uint8_t i = 0; i < 8; i++) {633if (((xb & 0x01) ^ (crc & 0x0001)) !=0 ) {634crc = crc >> 1;635crc = crc ^ 0xA001;636} else {637crc = crc >> 1;638}639xb = xb >> 1;640}641}642return crc;643}644645bool AP_BLHeli::isMcuConnected(void)646{647return blheli.connected[blheli.chan];648}649650void AP_BLHeli::setDisconnected(void)651{652blheli.connected[blheli.chan] = false;653blheli.deviceInfo[blheli.chan][0] = 0;654blheli.deviceInfo[blheli.chan][1] = 0;655}656657/*658send a set of bytes to an RC output channel659*/660bool AP_BLHeli::BL_SendBuf(const uint8_t *buf, uint16_t len)661{662bool send_crc = isMcuConnected();663if (blheli.chan >= num_motors) {664return false;665}666EXPECT_DELAY_MS(1000);667hal.scheduler->delay_microseconds(100);668if (!hal.rcout->serial_setup_output(blheli_chan_to_output_chan(blheli.chan), 19200, motor_mask)) {669debug_console("serial_setup_output() failed\n");670blheli.ack = ACK_D_GENERAL_ERROR;671return false;672}673// ensure that the next write does not go out immediately in case the receiving side is not yet674// ready675hal.scheduler->delay_microseconds(100);676677if (serial_start_ms == 0) {678serial_start_ms = AP_HAL::millis();679}680memcpy(blheli.buf, buf, len);681uint16_t crc = BL_CRC(buf, len);682blheli.buf[len] = uint8_t(crc & 0xFF);683blheli.buf[len+1] = uint8_t(crc>>8);684if (!hal.rcout->serial_write_bytes(blheli.buf, len+(send_crc?2:0))) {685debug_console("serial_write_bytes() failed\n");686blheli.ack = ACK_D_GENERAL_ERROR;687return false;688}689// 19200 baud is 52us per bit - wait for half a bit between sending and receiving to avoid reading690// the end of the last sent bit by accident691hal.scheduler->delay_microseconds(26);692return true;693}694695/*696read bytes from the ESC connection697*/698bool AP_BLHeli::BL_ReadBuf(uint8_t *buf, uint16_t len)699{700bool check_crc = isMcuConnected();701uint16_t req_bytes = len+(check_crc?3:1);702EXPECT_DELAY_MS(1000);703// byte time is 520us so 1000 per byte should be more than enough704uint16_t n = hal.rcout->serial_read_bytes(blheli.buf, req_bytes, req_bytes * 1000);705debug("BL_ReadBuf %u -> %u", len, n);706if (req_bytes != n) {707debug("short read");708blheli.ack = ACK_D_GENERAL_ERROR;709return false;710}711if (check_crc) {712uint16_t crc = BL_CRC(blheli.buf, len);713if ((crc & 0xff) != blheli.buf[len] ||714(crc >> 8) != blheli.buf[len+1]) {715debug("bad CRC");716blheli.ack = ACK_D_GENERAL_ERROR;717return false;718}719if (blheli.buf[len+2] != brSUCCESS) {720debug("bad ACK 0x%02x", blheli.buf[len+2]);721blheli.ack = ACK_D_GENERAL_ERROR;722return false;723}724} else {725if (blheli.buf[len] != brSUCCESS) {726debug("bad ACK1 0x%02x", blheli.buf[len]);727blheli.ack = ACK_D_GENERAL_ERROR;728return false;729}730}731if (len > 0) {732memcpy(buf, blheli.buf, len);733}734return true;735}736737uint8_t AP_BLHeli::BL_GetACK(uint16_t timeout_ms)738{739uint8_t ack;740EXPECT_DELAY_MS(timeout_ms);741if (hal.rcout->serial_read_bytes(&ack, 1, timeout_ms * 1000) == 1) {742return ack;743}744// return brNONE, meaning no ACK received in the timeout745return brNONE;746}747748bool AP_BLHeli::BL_SendCMDSetAddress()749{750// skip if adr == 0xFFFF751if (blheli.address == 0xFFFF) {752return true;753}754debug("BL_SendCMDSetAddress 0x%04x", blheli.address);755uint8_t sCMD[] = {CMD_SET_ADDRESS, 0, uint8_t(blheli.address>>8), uint8_t(blheli.address)};756if (!BL_SendBuf(sCMD, 4)) {757return false;758}759return BL_GetACK() == brSUCCESS;760}761762bool AP_BLHeli::BL_ReadA(uint8_t cmd, uint8_t *buf, uint16_t n)763{764if (BL_SendCMDSetAddress()) {765uint8_t sCMD[] = {cmd, uint8_t(n==256?0:n)};766if (!BL_SendBuf(sCMD, 2)) {767return false;768}769bool ret = BL_ReadBuf(buf, n);770if (ret && n == sizeof(esc_status) && blheli.address == esc_status_addr) {771// display esc_status structure if we see it772struct esc_status status;773memcpy(&status, buf, n);774debug("Prot %u Good %u Bad %u %x %x %x x%x\n",775(unsigned)status.protocol,776(unsigned)status.good_frames,777(unsigned)status.bad_frames,778(unsigned)status.unknown[0],779(unsigned)status.unknown[1],780(unsigned)status.unknown[2],781(unsigned)status.unknown2);782}783return ret;784}785return false;786}787788/*789connect to a blheli ESC790*/791bool AP_BLHeli::BL_ConnectEx(void)792{793debug("BL_ConnectEx %u/%u at %u", blheli.chan, num_motors, blheli_chan_to_output_chan(blheli.chan));794setDisconnected();795const uint8_t BootInit[] = {0,0,0,0,0,0,0,0,0,0,0,0,0x0D,'B','L','H','e','l','i',0xF4,0x7D};796if (!BL_SendBuf(BootInit, 21)) {797return false;798}799800uint8_t BootInfo[9];801if (!BL_ReadBuf(BootInfo, 8)) {802return false;803}804805// reply must start with 471806if (strncmp((const char *)BootInfo, "471", 3) != 0) {807blheli.ack = ACK_D_GENERAL_ERROR;808return false;809}810811// extract device information812blheli.deviceInfo[blheli.chan][2] = BootInfo[3];813blheli.deviceInfo[blheli.chan][1] = BootInfo[4];814blheli.deviceInfo[blheli.chan][0] = BootInfo[5];815816blheli.interface_mode[blheli.chan] = 0;817818uint16_t devword;819memcpy(&devword, blheli.deviceInfo[blheli.chan], sizeof(devword));820switch (devword) {821case 0x9307:822case 0x930A:823case 0x930F:824case 0x940B:825blheli.interface_mode[blheli.chan] = imATM_BLB;826debug("Interface type imATM_BLB");827break;828case 0xF310:829case 0xF330:830case 0xF410:831case 0xF390:832case 0xF850:833case 0xE8B1:834case 0xE8B2:835blheli.interface_mode[blheli.chan] = imSIL_BLB;836debug("Interface type imSIL_BLB");837break;838default:839// BLHeli_32 MCU ID hi > 0x00 and < 0x90 / lo always = 0x06840if ((blheli.deviceInfo[blheli.chan][1] > 0x00) && (blheli.deviceInfo[blheli.chan][1] < 0x90) && (blheli.deviceInfo[blheli.chan][0] == 0x06)) {841blheli.interface_mode[blheli.chan] = imARM_BLB;842debug("Interface type imARM_BLB");843} else {844blheli.ack = ACK_D_GENERAL_ERROR;845debug("Unknown interface type 0x%04x", devword);846break;847}848}849blheli.deviceInfo[blheli.chan][3] = blheli.interface_mode[blheli.chan];850if (blheli.interface_mode[blheli.chan] != 0) {851blheli.connected[blheli.chan] = true;852}853return true;854}855856bool AP_BLHeli::BL_SendCMDKeepAlive(void)857{858uint8_t sCMD[] = {CMD_KEEP_ALIVE, 0};859if (!BL_SendBuf(sCMD, 2)) {860return false;861}862if (BL_GetACK() != brERRORCOMMAND) {863return false;864}865return true;866}867868bool AP_BLHeli::BL_PageErase(void)869{870if (BL_SendCMDSetAddress()) {871uint8_t sCMD[] = {CMD_ERASE_FLASH, 0x01};872if (!BL_SendBuf(sCMD, 2)) {873return false;874}875return BL_GetACK(3000) == brSUCCESS;876}877return false;878}879880void AP_BLHeli::BL_SendCMDRunRestartBootloader(void)881{882uint8_t sCMD[] = {RestartBootloader, 0};883blheli.deviceInfo[blheli.chan][0] = 1;884BL_SendBuf(sCMD, 2);885}886887uint8_t AP_BLHeli::BL_SendCMDSetBuffer(const uint8_t *buf, uint16_t nbytes)888{889uint8_t sCMD[] = {CMD_SET_BUFFER, 0, uint8_t(nbytes>>8), uint8_t(nbytes&0xff)};890if (nbytes == 0) {891// set high byte since 0 bytes == 256 bytes in this protocol892sCMD[2] = 1;893}894if (!BL_SendBuf(sCMD, 4)) {895debug_console("BL_SendCMDSetBuffer send cmd failed");896return false;897}898uint8_t ack = BL_GetACK(5); // match betaflight timing899// generally no ack returned for CMD_SET_BUFFER when flashing firmware900if (ack != brNONE && ack != brSUCCESS) {901debug("BL_SendCMDSetBuffer ack failed 0x%02x", ack);902blheli.ack = ACK_D_GENERAL_ERROR;903return false;904}905906if (!BL_SendBuf(buf, nbytes)) {907debug("BL_SendCMDSetBuffer send failed");908blheli.ack = ACK_D_GENERAL_ERROR;909return false;910}911return (BL_GetACK(40) == brSUCCESS);912}913914bool AP_BLHeli::BL_WriteA(uint8_t cmd, const uint8_t *buf, uint16_t nbytes, uint32_t timeout_ms)915{916if (BL_SendCMDSetAddress()) {917if (!BL_SendCMDSetBuffer(buf, nbytes)) {918debug_console("BL_SendCMDSetBuffer failed\n");919blheli.ack = ACK_D_GENERAL_ERROR;920return false;921}922uint8_t sCMD[] = {cmd, 0x01};923if (!BL_SendBuf(sCMD, 2)) {924debug_console("BL_SendBuf failed\n");925return false;926}927uint8_t ack = BL_GetACK(timeout_ms);928if (ack != brSUCCESS) {929debug_console("BL_GetACK failed 0x%x\n", ack);930}931return (ack == brSUCCESS);932}933debug_console("BL_SendCMDSetAddress failed\n");934blheli.ack = ACK_D_GENERAL_ERROR;935return false;936}937938bool AP_BLHeli::BL_WriteFlash(const uint8_t *buf, uint16_t n)939{940return BL_WriteA(CMD_PROG_FLASH, buf, n, 500);941}942943bool AP_BLHeli::BL_VerifyFlash(const uint8_t *buf, uint16_t n)944{945if (BL_SendCMDSetAddress()) {946if (!BL_SendCMDSetBuffer(buf, n)) {947return false;948}949uint8_t sCMD[] = {CMD_VERIFY_FLASH_ARM, 0x01};950if (!BL_SendBuf(sCMD, 2)) {951return false;952}953uint8_t ack = BL_GetACK(40);954switch (ack) {955case brSUCCESS:956blheli.ack = ACK_OK;957break;958case brERRORVERIFY:959blheli.ack = ACK_I_VERIFY_ERROR;960break;961default:962blheli.ack = ACK_D_GENERAL_ERROR;963break;964}965return true;966}967return false;968}969970/*971process a blheli 4way command from GCS972*/973void AP_BLHeli::blheli_process_command(void)974{975debug("BLHeli cmd 0x%02x len=%u", blheli.command, blheli.param_len);976blheli.ack = ACK_OK;977switch (blheli.command) {978case cmd_InterfaceTestAlive: {979debug("cmd_InterfaceTestAlive");980if (!isMcuConnected()) {981blheli.ack = ACK_D_GENERAL_ERROR;982} else {983BL_SendCMDKeepAlive();984if (blheli.ack != ACK_OK) {985setDisconnected();986}987}988uint8_t b = 0;989blheli_send_reply(&b, 1);990break;991}992case cmd_ProtocolGetVersion: {993debug("cmd_ProtocolGetVersion");994uint8_t buf[1];995buf[0] = SERIAL_4WAY_PROTOCOL_VER;996blheli_send_reply(buf, sizeof(buf));997break;998}999case cmd_InterfaceGetName: {1000debug("cmd_InterfaceGetName");1001uint8_t buf[5] = { 4, 'A', 'R', 'D', 'U' };1002blheli_send_reply(buf, sizeof(buf));1003break;1004}1005case cmd_InterfaceGetVersion: {1006debug("cmd_InterfaceGetVersion");1007uint8_t buf[2] = { SERIAL_4WAY_VERSION_HI, SERIAL_4WAY_VERSION_LO };1008blheli_send_reply(buf, sizeof(buf));1009break;1010}1011case cmd_InterfaceExit: {1012debug("cmd_InterfaceExit");1013msp.escMode = PROTOCOL_NONE;1014uint8_t b = 0;1015blheli_send_reply(&b, 1);1016serial_end();1017if (motors_disabled) {1018motors_disabled = false;1019SRV_Channels::set_disabled_channel_mask(motors_disabled_mask);1020}1021if (uart_locked) {1022debug("Unlocked UART");1023uart->lock_port(0, 0);1024uart_locked = false;1025}1026memset(blheli.connected, 0, sizeof(blheli.connected));1027break;1028}1029case cmd_DeviceReset: {1030debug("cmd_DeviceReset(%u)", unsigned(blheli.buf[0]));1031if (blheli.buf[0] >= num_motors) {1032debug("bad reset channel %u", blheli.buf[0]);1033blheli.ack = ACK_I_INVALID_CHANNEL;1034blheli_send_reply(&blheli.buf[0], 1);1035break;1036}1037blheli.chan = blheli.buf[0];1038switch (blheli.interface_mode[blheli.chan]) {1039case imSIL_BLB:1040case imATM_BLB:1041case imARM_BLB:1042BL_SendCMDRunRestartBootloader();1043break;1044case imSK:1045break;1046}1047blheli_send_reply(&blheli.chan, 1);1048setDisconnected();1049break;1050}10511052case cmd_DeviceInitFlash: {1053uint8_t chan = blheli.buf[0];10541055debug("cmd_DeviceInitFlash(%u)", unsigned(blheli.buf[0]));1056if (blheli.buf[0] >= num_motors) {1057debug("bad channel %u", blheli.buf[0]);1058blheli.ack = ACK_I_INVALID_CHANNEL;1059blheli_send_reply(&chan, 1);1060break;1061}1062// betaflight tries three times to connect, this avoids the need to wait some arbitrary1063// period for the interface to be up.1064bool failed = true;1065for (uint8_t i = 0; i<3; i++) {1066blheli.chan = chan;1067blheli.ack = ACK_OK;1068if (BL_ConnectEx()) {1069uint8_t buf[4] = {blheli.deviceInfo[blheli.chan][0],1070blheli.deviceInfo[blheli.chan][1],1071blheli.deviceInfo[blheli.chan][2],1072blheli.deviceInfo[blheli.chan][3]}; // device ID1073blheli_send_reply(buf, sizeof(buf));1074failed = false;1075break;1076}1077}10781079if (failed) {1080blheli.ack = ACK_D_GENERAL_ERROR;1081blheli_send_reply(&chan, 1);1082setDisconnected();1083}1084break;1085}10861087case cmd_InterfaceSetMode: {1088debug("cmd_InterfaceSetMode(%u)", unsigned(blheli.buf[0]));1089blheli.interface_mode[blheli.chan] = blheli.buf[0];1090blheli_send_reply(&blheli.interface_mode[blheli.chan], 1);1091break;1092}10931094case cmd_DeviceRead: {1095uint16_t nbytes = blheli.buf[0]?blheli.buf[0]:256;1096debug("cmd_DeviceRead(%u) n=%u", blheli.chan, nbytes);1097uint8_t buf[nbytes];1098uint8_t cmd = blheli.interface_mode[blheli.chan]==imATM_BLB?CMD_READ_FLASH_ATM:CMD_READ_FLASH_SIL;1099if (!BL_ReadA(cmd, buf, nbytes)) {1100nbytes = 1;1101}1102blheli_send_reply(buf, nbytes);1103break;1104}11051106case cmd_DevicePageErase: {1107uint8_t page = blheli.buf[0];1108debug("cmd_DevicePageErase(%u) im=%u", page, blheli.interface_mode[blheli.chan]);1109switch (blheli.interface_mode[blheli.chan]) {1110case imSIL_BLB:1111case imARM_BLB: {1112if (blheli.interface_mode[blheli.chan] == imARM_BLB) {1113// Address =Page * 10241114blheli.address = page << 10;1115} else {1116// Address =Page * 5121117blheli.address = page << 9;1118}1119debug("ARM PageErase 0x%04x", blheli.address);1120BL_PageErase();1121blheli.address = 0;1122blheli_send_reply(&page, 1);1123break;1124}1125default:1126blheli.ack = ACK_I_INVALID_CMD;1127blheli_send_reply(&page, 1);1128break;1129}1130break;1131}11321133case cmd_DeviceWrite: {1134uint16_t nbytes = blheli.param_len;1135debug("cmd_DeviceWrite n=%u im=%u", nbytes, blheli.interface_mode[blheli.chan]);1136uint8_t buf[nbytes];1137memcpy(buf, blheli.buf, nbytes);1138switch (blheli.interface_mode[blheli.chan]) {1139case imSIL_BLB:1140case imATM_BLB:1141case imARM_BLB: {1142if (!BL_WriteFlash(buf, nbytes)) {1143// For reasons unknown BL_WriteFlash can bork the DMA engine, make some attempt to get1144// back to a sane state if this happens. We can't call serial_end() as that will1145// restart dshot output1146debug_console("cmd_DeviceWrite failed 0x%x: %u bytes", blheli.address, nbytes);1147hal.rcout->serial_reset(motor_mask);1148}1149break;1150}1151case imSK: {1152debug("Unsupported flash mode imSK");1153break;1154}1155}1156uint8_t b=0;1157blheli_send_reply(&b, 1);1158break;1159}11601161case cmd_DeviceVerify: {1162uint16_t nbytes = blheli.param_len;1163debug("cmd_DeviceWrite n=%u im=%u", nbytes, blheli.interface_mode[blheli.chan]);1164switch (blheli.interface_mode[blheli.chan]) {1165case imARM_BLB: {1166uint8_t buf[nbytes];1167memcpy(buf, blheli.buf, nbytes);1168BL_VerifyFlash(buf, nbytes);1169break;1170}1171default:1172blheli.ack = ACK_I_INVALID_CMD;1173break;1174}1175uint8_t b=0;1176blheli_send_reply(&b, 1);1177break;1178}11791180case cmd_DeviceReadEEprom: {1181uint16_t nbytes = blheli.buf[0]?blheli.buf[0]:256;1182uint8_t buf[nbytes];1183debug("cmd_DeviceReadEEprom n=%u im=%u", nbytes, blheli.interface_mode[blheli.chan]);1184switch (blheli.interface_mode[blheli.chan]) {1185case imATM_BLB: {1186if (!BL_ReadA(CMD_READ_EEPROM, buf, nbytes)) {1187blheli.ack = ACK_D_GENERAL_ERROR;1188}1189break;1190}1191default:1192blheli.ack = ACK_I_INVALID_CMD;1193break;1194}1195if (blheli.ack != ACK_OK) {1196nbytes = 1;1197buf[0] = 0;1198}1199blheli_send_reply(buf, nbytes);1200break;1201}12021203case cmd_DeviceWriteEEprom: {1204uint16_t nbytes = blheli.param_len;1205uint8_t buf[nbytes];1206memcpy(buf, blheli.buf, nbytes);1207debug("cmd_DeviceWriteEEprom n=%u im=%u", nbytes, blheli.interface_mode[blheli.chan]);1208switch (blheli.interface_mode[blheli.chan]) {1209case imATM_BLB:1210BL_WriteA(CMD_PROG_EEPROM, buf, nbytes, 3000);1211break;1212default:1213blheli.ack = ACK_D_GENERAL_ERROR;1214break;1215}1216uint8_t b = 0;1217blheli_send_reply(&b, 1);1218break;1219}12201221case cmd_DeviceEraseAll:1222case cmd_DeviceC2CK_LOW:1223default:1224// ack=unknown command1225blheli.ack = ACK_I_INVALID_CMD;1226debug("Unknown BLHeli protocol 0x%02x", blheli.command);1227uint8_t b = 0;1228blheli_send_reply(&b, 1);1229break;1230}1231}12321233/*1234process an input byte, return true if we have received a whole1235packet with correct CRC1236*/1237bool AP_BLHeli::process_input(uint8_t b)1238{1239bool valid_packet = false;12401241if (msp.escMode == PROTOCOL_4WAY && blheli.state == BLHELI_IDLE && b == '$') {1242debug("Change to MSP mode");1243msp.escMode = PROTOCOL_NONE;1244serial_end();1245}1246if (msp.escMode != PROTOCOL_4WAY && msp.state == MSP_IDLE && b == '/') {1247debug("Change to BLHeli mode");1248memset(blheli.connected, 0, sizeof(blheli.connected));1249msp.escMode = PROTOCOL_4WAY;1250}1251if (msp.escMode == PROTOCOL_4WAY) {1252blheli_4way_process_byte(b);1253} else {1254msp_process_byte(b);1255}1256if (msp.escMode == PROTOCOL_4WAY) {1257if (blheli.state == BLHELI_COMMAND_RECEIVED) {1258valid_packet = true;1259last_valid_ms = AP_HAL::millis();1260if (uart->lock_port(BLHELI_UART_LOCK_KEY, 0)) {1261uart_locked = true;1262}1263blheli_process_command();1264blheli.state = BLHELI_IDLE;1265msp.state = MSP_IDLE;1266}1267} else if (msp.state == MSP_COMMAND_RECEIVED) {1268if (msp.packetType == MSP_PACKET_COMMAND) {1269valid_packet = true;1270if (uart->lock_port(BLHELI_UART_LOCK_KEY, 0)) {1271uart_locked = true;1272}1273last_valid_ms = AP_HAL::millis();1274msp_process_command();1275}1276msp.state = MSP_IDLE;1277blheli.state = BLHELI_IDLE;1278}12791280return valid_packet;1281}12821283/*1284protocol handler for detecting BLHeli input1285*/1286bool AP_BLHeli::protocol_handler(uint8_t b, AP_HAL::UARTDriver *_uart)1287{1288uart = _uart;1289if (hal.util->get_soft_armed()) {1290// don't allow MSP control when armed1291return false;1292}1293return process_input(b);1294}12951296/*1297run a connection test to the ESCs. This is used to test the1298operation of the BLHeli ESC protocol1299*/1300void AP_BLHeli::run_connection_test(uint8_t chan)1301{1302run_test.set_and_notify(0);1303debug_uart = hal.console;1304uint8_t saved_chan = blheli.chan;1305if (chan >= num_motors) {1306GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ESC: bad channel %u", chan);1307return;1308}1309blheli.chan = chan;1310GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ESC: Running test on channel %u", blheli.chan);1311bool passed = false;1312for (uint8_t tries=0; tries<5; tries++) {1313EXPECT_DELAY_MS(3000);1314blheli.ack = ACK_OK;1315setDisconnected();1316if (BL_ConnectEx()) {1317uint8_t buf[256];1318uint8_t cmd = blheli.interface_mode[blheli.chan]==imATM_BLB?CMD_READ_FLASH_ATM:CMD_READ_FLASH_SIL;1319passed = true;1320blheli.address = blheli.interface_mode[blheli.chan]==imATM_BLB?0:0x7c00;1321passed &= BL_ReadA(cmd, buf, sizeof(buf));1322if (blheli.interface_mode[blheli.chan]==imARM_BLB) {1323if (passed) {1324// read status structure1325blheli.address = esc_status_addr;1326passed &= BL_SendCMDSetAddress();1327}1328if (passed) {1329struct esc_status status;1330passed &= BL_ReadA(CMD_READ_FLASH_SIL, (uint8_t *)&status, sizeof(status));1331}1332}1333BL_SendCMDRunRestartBootloader();1334break;1335}1336}1337serial_end();1338SRV_Channels::set_disabled_channel_mask(motors_disabled_mask);1339motors_disabled = false;1340blheli.chan = saved_chan;1341GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ESC: Test %s", passed?"PASSED":"FAILED");1342debug_uart = nullptr;1343}13441345/*1346update BLHeli1347*/1348void AP_BLHeli::update(void)1349{1350bool motor_control_active = false;1351for (uint8_t i = 0; i < num_motors; i++) {1352bool reversed = ((1U<< motor_map[i]) & channel_reversible_mask.get()) != 0;1353if (hal.rcout->read( motor_map[i]) != (reversed ? 1500 : 1000)) {1354motor_control_active = true;1355}1356}13571358uint32_t now = AP_HAL::millis();1359if (initialised && uart_locked &&1360((timeout_sec && now - last_valid_ms > uint32_t(timeout_sec.get())*1000U) ||1361(motor_control_active && now - last_valid_ms > MOTOR_ACTIVE_TIMEOUT))) {1362// we're not processing requests any more, shutdown serial1363// output1364if (serial_start_ms) {1365serial_end();1366}1367if (motors_disabled) {1368motors_disabled = false;1369SRV_Channels::set_disabled_channel_mask(motors_disabled_mask);1370}1371if (uart != nullptr) {1372debug("Unlocked UART");1373uart->lock_port(0, 0);1374uart_locked = false;1375}1376if (motor_control_active) {1377for (uint8_t i = 0; i < num_motors; i++) {1378bool reversed = ((1U<<motor_map[i]) & channel_reversible_mask.get()) != 0;1379hal.rcout->write(motor_map[i], reversed ? 1500 : 1000);1380}1381}1382}13831384if (initialised || (channel_mask.get() == 0 && channel_auto.get() == 0)) {1385if (initialised && run_test.get() > 0) {1386run_connection_test(run_test.get() - 1);1387}1388}1389}13901391void AP_BLHeli::serial_end()1392{1393hal.rcout->serial_end(motor_mask);1394serial_start_ms = 0;1395}13961397/*1398Initialize BLHeli, called by SRV_Channels::init()1399Used to install protocol handler1400The motor mask of enabled motors can be passed in1401*/1402void AP_BLHeli::init(uint32_t mask, AP_HAL::RCOutput::output_mode otype)1403{1404initialised = true;14051406run_test.set_and_notify(0);14071408#if HAL_GCS_ENABLED1409// only install pass-thru protocol handler if either auto or the motor mask are set1410if (channel_mask.get() != 0 || channel_auto.get() != 0) {1411if (last_control_port > 0 && last_control_port != control_port) {1412gcs().install_alternative_protocol((mavlink_channel_t)(MAVLINK_COMM_0+last_control_port), nullptr);1413last_control_port = -1;1414}1415if (gcs().install_alternative_protocol((mavlink_channel_t)(MAVLINK_COMM_0+control_port),1416FUNCTOR_BIND_MEMBER(&AP_BLHeli::protocol_handler,1417bool, uint8_t, AP_HAL::UARTDriver *))) {1418debug("BLHeli installed on port %u", (unsigned)control_port);1419last_control_port = control_port;1420}1421}1422#endif // HAL_GCS_ENABLED14231424#if HAL_WITH_IO_MCU1425if (AP_BoardConfig::io_enabled()) {1426// with IOMCU the local (FMU) channels start at 81427chan_offset = 8;1428}1429#endif14301431mask |= uint32_t(channel_mask.get());14321433/*1434allow mode override - this makes it possible to use DShot for1435rovers and subs, plus for quadplane fwd motors1436*/1437// +1 converts from AP_Motors::pwm_type to AP_HAL::RCOutput::output_mode and saves doing a param conversion1438// this is the only use of the param, but this is still a bit of a hack1439const int16_t type = output_type.get() + 1;1440if (otype == AP_HAL::RCOutput::MODE_PWM_NONE) {1441otype = ((type > AP_HAL::RCOutput::MODE_PWM_NONE) && (type < AP_HAL::RCOutput::MODE_NEOPIXEL)) ? AP_HAL::RCOutput::output_mode(type) : AP_HAL::RCOutput::MODE_PWM_NONE;1442}1443switch (otype) {1444case AP_HAL::RCOutput::MODE_PWM_ONESHOT:1445case AP_HAL::RCOutput::MODE_PWM_ONESHOT125:1446case AP_HAL::RCOutput::MODE_PWM_BRUSHED:1447case AP_HAL::RCOutput::MODE_PWM_DSHOT150:1448case AP_HAL::RCOutput::MODE_PWM_DSHOT300:1449case AP_HAL::RCOutput::MODE_PWM_DSHOT600:1450case AP_HAL::RCOutput::MODE_PWM_DSHOT1200:1451if (mask) {1452hal.rcout->set_output_mode(mask, otype);1453}1454break;1455default:1456break;1457}14581459uint32_t digital_mask = 0;1460// setting the digital mask changes the min/max PWM values1461// it's important that this is NOT done for non-digital channels as otherwise1462// PWM min can result in motors turning. set for individual overrides first1463if (mask && hal.rcout->is_dshot_protocol(otype)) {1464digital_mask = mask;1465}14661467#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_Rover)1468/*1469plane and copter can use AP_Motors to get an automatic mask1470*/1471#if APM_BUILD_TYPE(APM_BUILD_Rover)1472AP_MotorsUGV *motors = AP::motors_ugv();1473#else1474AP_Motors *motors = AP::motors();1475#endif1476if (motors) {1477uint32_t motormask = motors->get_motor_mask();1478// set the rest of the digital channels1479if (motors->is_digital_pwm_type()) {1480digital_mask |= motormask;1481}1482mask |= motormask;1483}1484#endif1485// tell SRV_Channels about ESC capabilities1486SRV_Channels::set_digital_outputs(digital_mask, uint32_t(channel_reversible_mask.get()) & digital_mask);1487// the dshot ESC type is required in order to send the reversed/reversible dshot command correctly1488hal.rcout->set_dshot_esc_type(SRV_Channels::get_dshot_esc_type());1489hal.rcout->set_reversible_mask(uint32_t(channel_reversible_mask.get()) & digital_mask);1490hal.rcout->set_reversed_mask(uint32_t(channel_reversed_mask.get()) & digital_mask);1491#ifdef HAL_WITH_BIDIR_DSHOT1492// possibly enable bi-directional dshot1493hal.rcout->set_motor_poles(motor_poles);1494#endif1495#if defined(HAL_WITH_BIDIR_DSHOT) || HAL_WITH_IO_MCU_BIDIR_DSHOT1496hal.rcout->set_bidir_dshot_mask(uint32_t(channel_bidir_dshot_mask.get()) & digital_mask);1497#endif1498// add motors from channel mask1499for (uint8_t i=0; i<16 && num_motors < max_motors; i++) {1500if (digital_mask & (1U<<i)) {1501motor_map[num_motors] = i;1502num_motors++;1503}1504}1505motor_mask = mask;1506debug("ESC: %u motors mask=0x%08lx", num_motors, digital_mask);15071508// check if we have a combination of reversible and normal1509mixed_type = (mask != (mask & channel_reversible_mask.get())) && (channel_reversible_mask.get() != 0);15101511if (num_motors != 0 && telem_rate > 0) {1512AP_SerialManager *serial_manager = AP_SerialManager::get_singleton();1513if (serial_manager) {1514telem_uart = serial_manager->find_serial(AP_SerialManager::SerialProtocol_ESCTelemetry,0);1515}1516}1517}15181519/*1520read an ESC telemetry packet1521*/1522void AP_BLHeli::read_telemetry_packet(void)1523{1524#if HAL_WITH_ESC_TELEM1525uint8_t buf[telem_packet_size];1526if (telem_uart->read(buf, telem_packet_size) < telem_packet_size) {1527// short read, we should have 10 bytes ready when this function is called1528return;1529}15301531// calculate crc1532uint8_t crc = 0;1533for (uint8_t i=0; i<telem_packet_size-1; i++) {1534crc = crc8_dvb(buf[i], crc, 0x07);1535}15361537if (buf[telem_packet_size-1] != crc) {1538// bad crc1539debug("Bad CRC on %u", last_telem_esc);1540return;1541}1542// record the previous rpm so that we can slew to the new one1543uint16_t new_rpm = ((buf[7]<<8) | buf[8]) * 200 / motor_poles;1544const uint8_t motor_idx = motor_map[last_telem_esc];1545// we have received valid data, mark the ESC as now active1546hal.rcout->set_active_escs_mask(1<<motor_idx);1547update_rpm(motor_idx, new_rpm);15481549TelemetryData t {1550.temperature_cdeg = int16_t(buf[0] * 100),1551.voltage = float(uint16_t((buf[1]<<8) | buf[2])) * 0.01,1552.current = float(uint16_t((buf[3]<<8) | buf[4])) * 0.01,1553.consumption_mah = float(uint16_t((buf[5]<<8) | buf[6])),1554};15551556update_telem_data(motor_idx, t,1557AP_ESC_Telem_Backend::TelemetryType::CURRENT1558| AP_ESC_Telem_Backend::TelemetryType::VOLTAGE1559| AP_ESC_Telem_Backend::TelemetryType::CONSUMPTION1560| AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE);15611562if (debug_level >= 2) {1563uint16_t trpm = new_rpm;1564if (has_bidir_dshot(last_telem_esc)) {1565trpm = hal.rcout->get_erpm(motor_idx);1566if (trpm != 0xFFFF) {1567trpm = trpm * 200 / motor_poles;1568}1569}1570DEV_PRINTF("ESC[%u] T=%u V=%f C=%f con=%f RPM=%u e=%.1f t=%u\n",1571last_telem_esc,1572t.temperature_cdeg,1573t.voltage,1574t.current,1575t.consumption_mah,1576trpm, hal.rcout->get_erpm_error_rate(motor_idx), (unsigned)AP_HAL::millis());1577}1578#endif // HAL_WITH_ESC_TELEM1579}15801581/*1582log bidir telemetry - only called if BLH telemetry is not active1583*/1584void AP_BLHeli::log_bidir_telemetry(void)1585{1586uint32_t now = AP_HAL::millis();15871588if (debug_level >= 2 && now - last_log_ms[last_telem_esc] > 100) {1589if (has_bidir_dshot(last_telem_esc)) {1590const uint8_t motor_idx = motor_map[last_telem_esc];1591uint16_t trpm = hal.rcout->get_erpm(motor_idx);1592if (trpm != 0xFFFF) { // don't log invalid values as they are never used1593trpm = trpm * 200 / motor_poles;1594}15951596if (trpm > 0) {1597last_log_ms[last_telem_esc] = now;1598DEV_PRINTF("ESC[%u] RPM=%u e=%.1f t=%u\n", last_telem_esc, trpm, hal.rcout->get_erpm_error_rate(motor_idx), (unsigned)AP_HAL::millis());1599}1600}1601}16021603if (!SRV_Channels::have_digital_outputs()) {1604return;1605}16061607// ask the next ESC for telemetry1608uint8_t idx_pos = last_telem_esc;1609uint8_t idx = (idx_pos + 1) % num_motors;1610for (; idx != idx_pos; idx = (idx + 1) % num_motors) {1611if (SRV_Channels::have_digital_outputs(1U << motor_map[idx])) {1612break;1613}1614}1615if (SRV_Channels::have_digital_outputs(1U << motor_map[idx])) {1616last_telem_esc = idx;1617}1618}16191620/*1621update BLHeli telemetry handling1622This is called on push() in SRV_Channels1623*/1624void AP_BLHeli::update_telemetry(void)1625{1626#ifdef HAL_WITH_BIDIR_DSHOT1627// we might only have bi-dir dshot1628if (channel_bidir_dshot_mask.get() != 0 && !telem_uart) {1629log_bidir_telemetry();1630}1631#endif1632if (!telem_uart || !SRV_Channels::have_digital_outputs()) {1633return;1634}1635uint32_t now = AP_HAL::micros();1636uint32_t telem_rate_us = 1000000U / uint32_t(telem_rate.get() * num_motors);1637if (telem_rate_us < 2000) {1638// make sure we have a gap between frames1639telem_rate_us = 2000;1640}1641if (!telem_uart_started || !telem_uart->is_owned_by_current_thread()) {1642// we need to use begin() here to ensure the correct thread owns the uart1643telem_uart->begin(115200);1644telem_uart_started = true;1645}16461647uint32_t nbytes = telem_uart->available();16481649if (nbytes > telem_packet_size) {1650// if we have more than 10 bytes then we don't know which ESC1651// they are from. Throw them all away1652telem_uart->discard_input();1653return;1654}1655if (nbytes > 0 &&1656nbytes < telem_packet_size &&1657(last_telem_byte_read_us == 0 ||1658now - last_telem_byte_read_us < 1000)) {1659// wait a bit longer, we don't have enough bytes yet1660if (last_telem_byte_read_us == 0) {1661last_telem_byte_read_us = now;1662}1663return;1664}1665if (nbytes > 0 && nbytes < telem_packet_size) {1666// we've waited long enough, discard bytes if we don't have 10 yet1667telem_uart->discard_input();1668return;1669}1670if (nbytes == telem_packet_size) {1671// we have a full packet ready to parse1672read_telemetry_packet();1673last_telem_byte_read_us = 0;1674}1675// we need to keep requesting telemetry even if we don't receive anything1676// as the request mask will be reset next cycle.1677if (now - last_telem_request_us >= telem_rate_us) {1678// ask the next ESC for telemetry1679uint8_t idx_pos = last_telem_esc;1680uint8_t idx = (idx_pos + 1) % num_motors;1681for (; idx != idx_pos; idx = (idx + 1) % num_motors) {1682if (SRV_Channels::have_digital_outputs(1U << motor_map[idx])) {1683break;1684}1685}1686uint32_t mask = 1U << motor_map[idx];1687if (SRV_Channels::have_digital_outputs(mask)) {1688hal.rcout->set_telem_request_mask(mask);1689last_telem_esc = idx;1690last_telem_request_us = now;1691}1692}1693}16941695#endif // HAVE_AP_BLHELI_SUPPORT169616971698