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_FETtecOneWire/AP_FETtecOneWire.cpp
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*/1415/* Initial protocol implementation was provided by FETtec */16/* Strongly modified by Amilcar Lucas, IAV GmbH */1718#include <AP_Math/AP_Math.h>19#include <AP_SerialManager/AP_SerialManager.h>20#include <SRV_Channel/SRV_Channel.h>21#include <GCS_MAVLink/GCS.h>2223#include "AP_FETtecOneWire.h"24#if AP_FETTEC_ONEWIRE_ENABLED2526extern const AP_HAL::HAL& hal;2728// Set to 0 when no ESC hardware is available and you want to test the UART send function29#ifndef HAL_AP_FETTEC_CONFIGURE_ESCS30#define HAL_AP_FETTEC_CONFIGURE_ESCS 131#endif3233#if HAL_AP_FETTEC_HALF_DUPLEX34static constexpr uint32_t HALF_DUPLEX_BAUDRATE = 2000000;35#endif36static constexpr uint32_t FULL_DUPLEX_BAUDRATE = 500000;3738const AP_Param::GroupInfo AP_FETtecOneWire::var_info[] {3940// @Param: MASK41// @DisplayName: Servo channel output bitmask42// @Description: Servo channel mask specifying FETtec ESC output.43// @Bitmask: 0:SERVO1,1:SERVO2,2:SERVO3,3:SERVO4,4:SERVO5,5:SERVO6,6:SERVO7,7:SERVO8,8:SERVO9,9:SERVO10,10:SERVO11,11:SERVO1244// @RebootRequired: True45// @User: Standard46AP_GROUPINFO_FLAGS("MASK", 1, AP_FETtecOneWire, _motor_mask_parameter, 0, AP_PARAM_FLAG_ENABLE),4748// @Param: RVMASK49// @DisplayName: Servo channel reverse rotation bitmask50// @Description: Servo channel mask to reverse rotation of FETtec ESC outputs.51// @Bitmask: 0:SERVO1,1:SERVO2,2:SERVO3,3:SERVO4,4:SERVO5,5:SERVO6,6:SERVO7,7:SERVO8,8:SERVO9,9:SERVO10,10:SERVO11,11:SERVO1252// @User: Standard53AP_GROUPINFO("RVMASK", 2, AP_FETtecOneWire, _reverse_mask_parameter, 0),5455#if HAL_WITH_ESC_TELEM56// @Param: POLES57// @DisplayName: Nr. electrical poles58// @Description: Number of motor electrical poles59// @Range: 2 5060// @User: Standard61AP_GROUPINFO("POLES", 3, AP_FETtecOneWire, _pole_count_parameter, 14),62#endif6364AP_GROUPEND65};6667AP_FETtecOneWire *AP_FETtecOneWire::_singleton;6869AP_FETtecOneWire::AP_FETtecOneWire()70{71AP_Param::setup_object_defaults(this, var_info);7273#if CONFIG_HAL_BOARD == HAL_BOARD_SITL74if (_singleton != nullptr) {75AP_HAL::panic("AP_FETtecOneWire must be singleton");76}77#endif78_singleton = this;79}8081/**82initialize the serial port8384*/85void AP_FETtecOneWire::init_uart()86{87if (_uart != nullptr) {88return;89}90const AP_SerialManager& serial_manager = AP::serialmanager();91_uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FETtecOneWire, 0);92if (_uart == nullptr) {93return; // no serial port available, so nothing to do here94}95_uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);96_uart->set_unbuffered_writes(true);9798uint32_t uart_baud { FULL_DUPLEX_BAUDRATE };99#if HAL_AP_FETTEC_HALF_DUPLEX100if (_uart->get_options() & _uart->OPTION_HDPLEX) { //Half-Duplex is enabled101_use_hdplex = true;102uart_baud = HALF_DUPLEX_BAUDRATE;103GCS_SEND_TEXT(MAV_SEVERITY_INFO, "FTW using Half-Duplex");104} else {105GCS_SEND_TEXT(MAV_SEVERITY_INFO, "FTW using Full-Duplex");106}107#endif108109_uart->begin(uart_baud);110}111112/// initialize the device driver: configure serial port, wake-up and configure ESCs113void AP_FETtecOneWire::init()114{115init_uart();116if (_uart == nullptr) {117return; // no serial port available, so nothing to do here118}119120_motor_mask = uint32_t(_motor_mask_parameter); // take a copy that will not change after we leave this function121_esc_count = __builtin_popcount(_motor_mask);122#if HAL_WITH_ESC_TELEM123// OneWire supports telemetry in at most 15 ESCs, because of the 4 bit limitation124// on the fast-throttle command. But we are still limited to the125// number of ESCs the telem library will collect data for.126if (_esc_count == 0 || _motor_mask >= (1U << MIN(15, ESC_TELEM_MAX_ESCS))) {127#else128// OneWire supports at most 24 ESCs without telemetry129if (_esc_count == 0 || _motor_mask >= (1U << MIN(24, NUM_SERVO_CHANNELS))) {130#endif131_invalid_mask = true;132return;133}134135// we have a uart and the desired ESC combination id valid, allocate some memory:136_escs = NEW_NOTHROW ESC[_esc_count];137if (_escs == nullptr) {138return;139}140141// initialise ESC ids. This enforces that the FETtec ESC ids142// inside FETtec ESCs need to be contiguous and start at ID 1143// which is required by fast-throttle commands.144uint8_t esc_offset = 0; // offset into our device-driver dynamically-allocated array of ESCs145uint8_t esc_id = 1; // ESC ids inside FETtec protocol are one-indexed146uint8_t servo_chan_offset = 0; // offset into _motor_mask_parameter array147for (uint32_t mask = _motor_mask; mask != 0; mask >>= 1, servo_chan_offset++) {148if (mask & 0x1) {149_escs[esc_offset].servo_ofs = servo_chan_offset;150_escs[esc_offset].id = esc_id++;151esc_offset++;152}153}154_invalid_mask = false; // mask is good155156GCS_SEND_TEXT(MAV_SEVERITY_INFO, "FETtec: allocated %u motors", _esc_count);157158// We expect to be able to send a fast-throttle command in each loop.159// 8 bits - OneWire Header160// 4 bits - telemetry request161// 11 bits - throttle value per ESC162// 8 bits - frame CRC163const uint16_t net_bit_count = 8 + 4 + (_esc_count * 11) + 8;164// 7 dummy for rounding up the division by 8165const uint16_t fast_throttle_byte_count = (net_bit_count + 7)/8;166uint16_t telemetry_byte_count { 0U };167#if HAL_WITH_ESC_TELEM168// Telemetry is fetched from each loop in turn.169telemetry_byte_count = sizeof(u.packed_tlm) + 1; // assume 9 pause bits between TX and RX170_fast_throttle_byte_count = fast_throttle_byte_count;171#endif172uint32_t uart_baud { FULL_DUPLEX_BAUDRATE };173#if HAL_AP_FETTEC_HALF_DUPLEX174if (_use_hdplex == true) { //Half-Duplex is enabled175uart_baud = HALF_DUPLEX_BAUDRATE;176}177#endif178_min_fast_throttle_period_us = (fast_throttle_byte_count + telemetry_byte_count) * 9 * 1000000 / uart_baud + 300; // 300us extra reserve179180// tell SRV_Channels about ESC capabilities181// this is a bit soonish because we have not seen the ESCs on the bus yet,182// but saves us having to use a state variable to ensure doing this latter just once183SRV_Channels::set_digital_outputs(_motor_mask, 0);184185_init_done = true;186}187188/**189transmits data to ESCs190@param bytes bytes to transmit191@param length number of bytes to transmit192@return false there's no space in the UART for this message193*/194bool AP_FETtecOneWire::transmit(const uint8_t* bytes, const uint8_t length)195{196const uint32_t now = AP_HAL::micros();197if (now - _last_transmit_us < _min_fast_throttle_period_us) {198// in case the SRV_Channels::push() is running at very high rates, limit the period199// this function gets executed because FETtec needs a time gap between frames200// this also prevents one loop to do multiple actions, like reinitialize an ESC and sending a fast-throttle command without a gap.201_period_too_short++;202return false;203}204_last_transmit_us = now;205if (length > _uart->txspace()) {206return false;207}208209_uart->write(bytes, length);210#if HAL_AP_FETTEC_HALF_DUPLEX211if (_use_hdplex) {212_ignore_own_bytes += length;213}214#endif215return true;216}217218/**219transmits a config request to ESCs220@param bytes bytes to transmit221@param length number of bytes to transmit222@return false if vehicle is armed or if transmit(bytes, length) would return false223*/224bool AP_FETtecOneWire::transmit_config_request(const uint8_t* bytes, const uint8_t length)225{226if (hal.util->get_soft_armed()) {227return false;228}229return transmit(bytes, length);230}231232/// shifts data to start of buffer based on magic header bytes233void AP_FETtecOneWire::move_frame_source_in_receive_buffer(const uint8_t search_start_pos)234{235uint8_t i;236for (i=search_start_pos; i<_receive_buf_used; i++) {237// FIXME: full-duplex should add MASTER here as we see our own data238if ((FrameSource)u.receive_buf[i] == FrameSource::BOOTLOADER ||239(FrameSource)u.receive_buf[i] == FrameSource::ESC) {240break;241}242}243consume_bytes(i);244}245246/// cut n bytes from start of buffer247void AP_FETtecOneWire::consume_bytes(const uint8_t n)248{249if (n == 0) {250return;251}252// assure the length of the memmove is positive253if (_receive_buf_used < n) {254return;255}256memmove(u.receive_buf, &u.receive_buf[n], _receive_buf_used-n);257_receive_buf_used = _receive_buf_used - n;258}259260/// returns true if the first message in the buffer is OK261bool AP_FETtecOneWire::buffer_contains_ok(const uint8_t length)262{263if (length != sizeof(u.packed_ok)) {264_message_invalid_in_state_count++;265return false;266}267if ((MsgType)u.packed_ok.msg.msgid != MsgType::OK) {268return false;269}270return true;271}272273void AP_FETtecOneWire::handle_message(ESC &esc, const uint8_t length)274{275// only accept messages from the bootloader when we could276// legitimately get a message from the bootloader. Swipes the OK277// message for convenience278const FrameSource frame_source = (FrameSource)u.packed_ok.frame_source;279if (frame_source != FrameSource::ESC) {280if (esc.state != ESCState::WAITING_OK_FOR_RUNNING_SW_TYPE) {281return;282}283}284285switch (esc.state) {286case ESCState::UNINITIALISED:287case ESCState::WANT_SEND_OK_TO_GET_RUNNING_SW_TYPE:288return;289case ESCState::WAITING_OK_FOR_RUNNING_SW_TYPE:290// "OK" is the only valid response291if (!buffer_contains_ok(length)) {292return;293}294switch (frame_source) {295case FrameSource::MASTER:296// probably half-duplex; should be caught before we get here297INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);298break;299case FrameSource::BOOTLOADER:300esc.set_state(ESCState::WANT_SEND_START_FW);301esc.is_awake = true;302break;303case FrameSource::ESC:304#if HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO305esc.set_state(ESCState::WANT_SEND_REQ_TYPE);306#else307#if HAL_WITH_ESC_TELEM308esc.set_state(ESCState::WANT_SEND_SET_TLM_TYPE);309#else310esc.set_state(ESCState::WANT_SEND_SET_FAST_COM_LENGTH);311#endif312#endif // HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO313esc.is_awake = true;314break;315}316break;317318case ESCState::WANT_SEND_START_FW:319return;320case ESCState::WAITING_OK_FOR_START_FW:321if (buffer_contains_ok(length)) {322#if HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO323esc.set_state(ESCState::WANT_SEND_REQ_TYPE);324#else325#if HAL_WITH_ESC_TELEM326esc.set_state(ESCState::WANT_SEND_SET_TLM_TYPE);327#else328esc.set_state(ESCState::WANT_SEND_SET_FAST_COM_LENGTH);329#endif330#endif // HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO331}332break;333334#if HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO335case ESCState::WANT_SEND_REQ_TYPE:336return;337case ESCState::WAITING_ESC_TYPE:338if (length != sizeof(u.packed_esc_type)) {339_message_invalid_in_state_count++;340return;341}342esc.type = u.packed_esc_type.msg.type;343esc.set_state(ESCState::WANT_SEND_REQ_SW_VER);344break;345346case ESCState::WANT_SEND_REQ_SW_VER:347return;348case ESCState::WAITING_SW_VER:349if (length != sizeof(u.packed_sw_ver)) {350_message_invalid_in_state_count++;351return;352}353esc.firmware_version = u.packed_sw_ver.msg.version;354esc.firmware_subversion = u.packed_sw_ver.msg.subversion;355esc.set_state(ESCState::WANT_SEND_REQ_SN);356break;357358case ESCState::WANT_SEND_REQ_SN:359return;360case ESCState::WAITING_SN:361if (length != sizeof(u.packed_sn)) {362_message_invalid_in_state_count++;363return;364}365static_assert(ARRAY_SIZE(u.packed_sn.msg.sn) == ARRAY_SIZE(esc.serial_number), "Serial number array length missmatch");366memcpy(esc.serial_number, u.packed_sn.msg.sn, ARRAY_SIZE(u.packed_sn.msg.sn));367#if HAL_WITH_ESC_TELEM368esc.set_state(ESCState::WANT_SEND_SET_TLM_TYPE);369#else370esc.set_state(ESCState::WANT_SEND_SET_FAST_COM_LENGTH);371#endif372break;373#endif // HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO374375#if HAL_WITH_ESC_TELEM376case ESCState::WANT_SEND_SET_TLM_TYPE:377return;378case ESCState::WAITING_SET_TLM_TYPE_OK:379if (buffer_contains_ok(length)) {380esc.set_state(ESCState::WANT_SEND_SET_FAST_COM_LENGTH);381}382break;383#endif384385case ESCState::WANT_SEND_SET_FAST_COM_LENGTH:386return;387case ESCState::WAITING_SET_FAST_COM_LENGTH_OK:388if (buffer_contains_ok(length)) {389esc.set_state(ESCState::RUNNING);390}391break;392case ESCState::RUNNING:393// we only expect telemetry messages in this state394#if HAL_WITH_ESC_TELEM395if (!esc.telem_expected) {396esc.unexpected_telem++;397#if CONFIG_HAL_BOARD == HAL_BOARD_SITL398AP_HAL::panic("unexpected telemetry");399#endif400return;401}402esc.telem_expected = false;403return handle_message_telem(esc);404#else405return;406#endif // HAL_WITH_ESC_TELEM407408}409}410411#if HAL_WITH_ESC_TELEM412void AP_FETtecOneWire::handle_message_telem(ESC &esc)413{414// the following two methods are coming from AP_ESC_Telem:415const TLM &tlm = u.packed_tlm.msg;416417// update rpm and error rate418float error_rate_pct = 0;419if (_fast_throttle_cmd_count > _esc_count) {420error_rate_pct = (tlm.tx_err_count-esc.error_count_at_throttle_count_overflow)*(float)100/(float)_fast_throttle_cmd_count;421} else {422// the telemetry is requested in a round-robin, sequential fashion423// so the in the first _esc_count times all ESCs get to initialize this424esc.error_count_at_throttle_count_overflow = tlm.tx_err_count;425}426update_rpm(esc.servo_ofs,427tlm.rpm*(100*2/_pole_count_parameter),428error_rate_pct);429430// update power and temperature telem data431TelemetryData t {};432t.temperature_cdeg = tlm.temp * 100;433t.voltage = tlm.voltage * 0.01f;434t.current = tlm.current * 0.01f;435t.consumption_mah = tlm.consumption_mah;436update_telem_data(437esc.servo_ofs,438t,439TelemetryType::TEMPERATURE|440TelemetryType::VOLTAGE|441TelemetryType::CURRENT|442TelemetryType::CONSUMPTION);443444esc.last_telem_us = AP_HAL::micros();445}446#endif // HAL_WITH_ESC_TELEM447448// reads data from the UART, calling handle_message on any message found449void AP_FETtecOneWire::read_data_from_uart()450{451/*452a frame looks like:453byte 1 = frame header (0x02 = bootloader, 0x03 = ESC firmware)454byte 2 = sender ID (5bit)455byte 3 & 4 = frame type (always 0x00, 0x00 used for bootloader. here just for compatibility)456byte 5 = frame length over all bytes457byte 6 - X = answer type, followed by the payload458byte X+1 = 8bit CRC459*/460461#if HAL_AP_FETTEC_HALF_DUPLEX462//ignore own bytes463if (_use_hdplex) {464while (_ignore_own_bytes > 0 && _uart->available()) {465_ignore_own_bytes--;466_uart->read();467}468}469#endif470471uint32_t bytes_to_read = MIN(_uart->available(), 128U);472uint32_t last_bytes_to_read = 0;473while (bytes_to_read &&474bytes_to_read != last_bytes_to_read) {475last_bytes_to_read = bytes_to_read;476477// read as much from the uart as we can:478const uint8_t space = ARRAY_SIZE(u.receive_buf) - _receive_buf_used;479const uint32_t nbytes = _uart->read(&u.receive_buf[_receive_buf_used], space);480_receive_buf_used += nbytes;481bytes_to_read -= nbytes;482483move_frame_source_in_receive_buffer();484485// borrow the "OK" message to retrieve the frame length from the buffer:486const uint8_t frame_length = u.packed_ok.frame_length;487if (_receive_buf_used < frame_length) {488continue;489}490491if (crc8_dvb_update(0, u.receive_buf, frame_length-1) != u.receive_buf[frame_length-1]) {492// bad message; shift away this frame_source byte to try to find493// another message494#if CONFIG_HAL_BOARD == HAL_BOARD_SITL495AP_HAL::panic("bad message");496#endif497crc_rec_err_cnt++;498move_frame_source_in_receive_buffer(1);499continue;500}501502// borrow the "OK" message to retrieve the frame_source from the buffer:503const FrameSource frame_source = (FrameSource)u.packed_ok.frame_source;504if (frame_source == FrameSource::MASTER) {505// this is our own message - we'd best be running in506// half-duplex or we're in trouble!507consume_bytes(frame_length);508continue;509}510511// borrow the "OK" message to retrieve the esc id from the buffer:512const uint8_t esc_id = u.packed_ok.esc_id;513bool handled = false;514// FIXME: we could scribble down the last ESC we sent a515// message to here and use it rather than doing this linear516// search:517for (uint8_t i=0; i<_esc_count; i++) {518auto &esc = _escs[i];519if (esc.id != esc_id) {520continue;521}522handle_message(esc, frame_length);523handled = true;524break;525}526if (!handled) {527_unknown_esc_message++;528}529530consume_bytes(frame_length);531}532}533534/**535packs a single fast-throttle command frame containing the throttle for all configured OneWire ESCs.536@param motor_values a 16bit array containing the throttle values that should be sent to the motors. 0-2000 where 1001-2000 is positive rotation and 0-999 reversed rotation537@param esc_id_to_request_telem_from the ESC to request telemetry from538*/539void AP_FETtecOneWire::pack_fast_throttle_command(const uint16_t *motor_values, uint8_t *fast_throttle_command, const uint8_t length, const uint8_t esc_id_to_request_telem_from)540{541// byte 1:542// bit 0,1,2,3 = ESC ID, Bit 4 = MSB bit of first ESC (11bit) throttle value, bit 5,6,7 = frame header543// so AAAABCCC544// A = ID from the ESC telemetry is requested from. ESC ID == 0 means no request.545// B = MSB from first throttle value546// C = frame header547fast_throttle_command[0] = esc_id_to_request_telem_from << 4; // 0 here means no telemetry request548fast_throttle_command[0] |= ((motor_values[0] >> 10) & 0x01) << 3;549fast_throttle_command[0] |= (uint8_t)FrameSource::MASTER;550551// byte 2:552// AAABBBBB553// A = next 3 bits from (11bit) throttle value554// B = 5bit target ID555fast_throttle_command[1] = (((motor_values[0] >> 7) & 0x07)) << 5;556fast_throttle_command[1] |= 0x1F; // All IDs557558// following bytes are the rest 7 bit of the first (11bit) throttle value,559// and all bits from all other throttle values, followed by the CRC byte560uint8_t mot = 0;561uint8_t bits_remaining_in_this_pwm = 7;562for (uint8_t out_byte_offset = 2; out_byte_offset<length; out_byte_offset++) {563if (bits_remaining_in_this_pwm >= 8) {564// const uint8_t mask = 0xFF << (11-bits_remaining_in_this_pwm);565fast_throttle_command[out_byte_offset] = (motor_values[mot] >> (bits_remaining_in_this_pwm-8)) & 0xFF;566bits_remaining_in_this_pwm -= 8;567} else {568const uint8_t mask = (1U<<bits_remaining_in_this_pwm)-1;569const uint8_t bits_to_copy_from_second_pwm = 8-bits_remaining_in_this_pwm;570fast_throttle_command[out_byte_offset] = (motor_values[mot] & mask) << bits_to_copy_from_second_pwm;571// move on to the next motor output572mot++;573if (mot < _esc_count) {574fast_throttle_command[out_byte_offset] |= motor_values[mot] >> (11-bits_to_copy_from_second_pwm);575}576bits_remaining_in_this_pwm = 11 - bits_to_copy_from_second_pwm;577}578}579580fast_throttle_command[length-1] =581crc8_dvb_update(0, fast_throttle_command, length-1);582}583584void AP_FETtecOneWire::escs_set_values(const uint16_t* motor_values)585{586uint8_t esc_id_to_request_telem_from = 0;587#if HAL_WITH_ESC_TELEM588ESC &esc_to_req_telem_from = _escs[_esc_ofs_to_request_telem_from++];589if (_esc_ofs_to_request_telem_from >= _esc_count) {590_esc_ofs_to_request_telem_from = 0;591}592esc_id_to_request_telem_from = esc_to_req_telem_from.id;593#endif594595uint8_t fast_throttle_command[_fast_throttle_byte_count];596pack_fast_throttle_command(motor_values, fast_throttle_command, sizeof(fast_throttle_command), esc_id_to_request_telem_from);597598#if HAL_AP_FETTEC_HALF_DUPLEX599// last byte of signal can be used to make sure the first TLM byte is correct, in case of spike corruption600// FIXME: use this somehow601_last_crc = fast_throttle_command[_fast_throttle_byte_count - 1];602#endif603604// No command was yet sent, so no reply is expected and all information605// on the receive buffer is either garbage or noise. Discard it606_uart->discard_input();607_receive_buf_used = 0;608609// send throttle commands to all configured ESCs in a single packet transfer610if (transmit(fast_throttle_command, sizeof(fast_throttle_command))) {611#if HAL_WITH_ESC_TELEM612esc_to_req_telem_from.telem_expected = true; // used to make sure that the returned telemetry comes from this ESC and not another613esc_to_req_telem_from.telem_requested = true; // used to check if this ESC is periodically sending telemetry614_fast_throttle_cmd_count++;615#endif616}617}618619bool AP_FETtecOneWire::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const620{621if (_motor_mask_parameter == 0) {622return true; // No FETtec ESCs are expected, no need to run further pre-arm checks623}624625if (_uart == nullptr) {626hal.util->snprintf(failure_msg, failure_msg_len, "No uart");627return false;628}629if (_invalid_mask) {630hal.util->snprintf(failure_msg, failure_msg_len, "Invalid motor mask");631return false;632}633#if HAL_WITH_ESC_TELEM634if (_pole_count_parameter < 2) {635hal.util->snprintf(failure_msg, failure_msg_len, "Invalid pole count %u", uint8_t(_pole_count_parameter));636return false;637}638uint8_t no_telem = 0;639const uint32_t now = AP_HAL::micros();640#endif641642uint8_t not_running = 0;643for (uint8_t i=0; i<_esc_count; i++) {644auto &esc = _escs[i];645if (esc.state != ESCState::RUNNING) {646not_running++;647continue;648}649#if HAL_WITH_ESC_TELEM650if (now - esc.last_telem_us > max_telem_interval_us) {651no_telem++;652}653#endif654}655if (not_running != 0) {656hal.util->snprintf(failure_msg, failure_msg_len, "%u of %u ESCs are not running", not_running, _esc_count);657return false;658}659if (!_init_done) {660hal.util->snprintf(failure_msg, failure_msg_len, "Not initialised");661return false;662}663#if HAL_WITH_ESC_TELEM664if (no_telem != 0) {665hal.util->snprintf(failure_msg, failure_msg_len, "%u of %u ESCs are not sending telemetry", no_telem, _esc_count);666return false;667}668#endif669670return true;671}672673void AP_FETtecOneWire::configure_escs()674{675if (_uart->available()) {676// don't attempt to configure if we've unread data677return;678}679680// note that we return as soon as we've transmitted anything in681// case we're in one-wire mode682for (uint8_t i=0; i<_esc_count; i++) {683auto &esc = _escs[i];684switch (esc.state) {685case ESCState::UNINITIALISED:686esc.state = ESCState::WANT_SEND_OK_TO_GET_RUNNING_SW_TYPE;687FALLTHROUGH;688case ESCState::WANT_SEND_OK_TO_GET_RUNNING_SW_TYPE:689// probe for bootloader or running firmware690if (transmit_config_request(PackedMessage<OK>{esc.id, OK{}})) {691esc.is_awake = false; // Assume the ESC is asleep or unavailable692esc.set_state(ESCState::WAITING_OK_FOR_RUNNING_SW_TYPE);693}694return;695case ESCState::WAITING_OK_FOR_RUNNING_SW_TYPE:696if (!esc.is_awake) {697esc.set_state(ESCState::WANT_SEND_OK_TO_GET_RUNNING_SW_TYPE); // go back to try to wake up the ESC698}699return;700case ESCState::WANT_SEND_START_FW:701if (transmit_config_request(PackedMessage<START_FW>{esc.id, START_FW{}})) {702esc.set_state(ESCState::WAITING_OK_FOR_START_FW);703}704return;705case ESCState::WAITING_OK_FOR_START_FW:706return;707#if HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO708case ESCState::WANT_SEND_REQ_TYPE:709if (transmit_config_request(PackedMessage<REQ_TYPE>{esc.id, REQ_TYPE{}})) {710esc.set_state(ESCState::WAITING_ESC_TYPE);711}712return;713case ESCState::WAITING_ESC_TYPE:714return;715case ESCState::WANT_SEND_REQ_SW_VER:716if (transmit_config_request(PackedMessage<REQ_SW_VER>{esc.id, REQ_SW_VER{}})) {717esc.set_state(ESCState::WAITING_SW_VER);718}719return;720case ESCState::WAITING_SW_VER:721return;722case ESCState::WANT_SEND_REQ_SN:723if (transmit_config_request(PackedMessage<REQ_SN>{esc.id, REQ_SN{}})) {724esc.set_state(ESCState::WAITING_SN);725}726return;727case ESCState::WAITING_SN:728return;729#endif // HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO730#if HAL_WITH_ESC_TELEM731case ESCState::WANT_SEND_SET_TLM_TYPE:732if (transmit_config_request(PackedMessage<SET_TLM_TYPE>{esc.id, SET_TLM_TYPE{1}})) {733esc.set_state(ESCState::WAITING_SET_TLM_TYPE_OK);734}735return;736case ESCState::WAITING_SET_TLM_TYPE_OK:737return;738#endif739case ESCState::WANT_SEND_SET_FAST_COM_LENGTH:740if (transmit_config_request(PackedMessage<SET_FAST_COM_LENGTH>{esc.id,741SET_FAST_COM_LENGTH{742_fast_throttle_byte_count,743_escs[0].id,744_esc_count745}})) {746esc.set_state(ESCState::WAITING_SET_FAST_COM_LENGTH_OK);747}748return;749case ESCState::WAITING_SET_FAST_COM_LENGTH_OK:750return;751case ESCState::RUNNING:752_running_mask |= (1U << esc.servo_ofs);753break;754}755}756}757758/// periodically called from SRV_Channels::push()759void AP_FETtecOneWire::update()760{761if (!_init_done) {762init();763return; // the rest of this function can only run after fully initted764}765766// read all data from incoming serial:767read_data_from_uart();768769const uint32_t now = AP_HAL::micros();770771#if HAL_WITH_ESC_TELEM772if (!hal.util->get_soft_armed()) {773774_reverse_mask = _reverse_mask_parameter; // update this only when disarmed775776// if we haven't seen an ESC in a while, the user might777// have power-cycled them. Try re-initialising.778for (uint8_t i=0; i<_esc_count; i++) {779auto &esc = _escs[i];780if (!esc.telem_requested || now - esc.last_telem_us < 1000000U ) {781// telem OK782continue;783}784_running_mask &= ~(1U << esc.servo_ofs);785GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "No telem from esc id=%u. Resetting it.", esc.id);786//GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "unknown %u, invalid %u, too short %u, unexpected: %u, crc_err %u", _unknown_esc_message, _message_invalid_in_state_count, _period_too_short, esc.unexpected_telem, crc_rec_err_cnt);787esc.set_state(ESCState::WANT_SEND_OK_TO_GET_RUNNING_SW_TYPE);788esc.telem_requested = false;789}790}791#endif // HAL_WITH_ESC_TELEM792793if (now - _last_transmit_us < 700U) {794// in case the SRV_Channels::push() is running at very high rates, limit the period795// this function gets executed because FETtec needs a time gap between frames796_period_too_short++;797return;798}799800#if defined(STM32F4)801if (_uart->tx_pending()) {802// there is unsent data in the send buffer,803// do not send more data because FETtec needs a time gap between frames804_period_too_short++;805return;806}807#endif808809#if HAL_AP_FETTEC_CONFIGURE_ESCS810// run ESC configuration state machines if needed811if (_running_mask != _motor_mask) {812configure_escs();813return; // do not send fast-throttle command if a configuration command just got sent814}815#endif816817// get ESC set points818uint16_t motor_pwm[_esc_count];819for (uint8_t i = 0; i < _esc_count; i++) {820const ESC &esc = _escs[i];821const SRV_Channel* c = SRV_Channels::srv_channel(esc.servo_ofs);822// check if safety switch has been pushed823if ( (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED)824|| (c == nullptr)) { // this should never ever happen, but just in case ...825motor_pwm[i] = 1000; // stop motor826continue;827}828motor_pwm[i] = constrain_int16(c->get_output_pwm(), 1000, 2000);829fet_debug("esc=%u in: %u", esc.id, motor_pwm[i]);830if (_reverse_mask & (1U << i)) {831motor_pwm[i] = 2000-motor_pwm[i];832}833}834835// send motor setpoints to ESCs, and request for telemetry data836escs_set_values(motor_pwm);837}838839#if HAL_AP_FETTEC_ESC_BEEP840/**841makes all connected ESCs beep842@param beep_frequency a 8 bit value from 0-255. higher make a higher beep843*/844void AP_FETtecOneWire::beep(const uint8_t beep_frequency)845{846for (uint8_t i=0; i<_esc_count; i++) {847auto &esc = _escs[i];848if (esc.state != ESCState::RUNNING) {849continue;850}851transmit_config_request(PackedMessage<Beep>{esc.id, Beep{beep_frequency}});852}853}854#endif // HAL_AP_FETTEC_ESC_BEEP855856#if HAL_AP_FETTEC_ESC_LIGHT857/**858sets the racewire color for all ESCs859r = red brightness860g = green brightness861b = blue brightness862*/863void AP_FETtecOneWire::led_color(const uint8_t r, const uint8_t g, const uint8_t b)864{865for (uint8_t i=0; i<_esc_count; i++) {866auto &esc = _escs[i];867if (esc.state != ESCState::RUNNING) {868continue;869}870transmit_config_request(PackedMessage<LEDColour>{esc.id, LEDColour{r, g, b}});871}872}873#endif // HAL_AP_FETTEC_ESC_LIGHT874875#endif // AP_FETTEC_ONEWIRE_ENABLED876877878