AP_FETtecOneWire: Convert into an ArduPilot device driver

Co-authored-by: Torsten Z <t.zunker@fettec.net>
    Co-authored-by: Peter Barker <pb-gh@barker.dropbear.id.au>

- use ArduPilot's coding guidelines and naming conventions
- control motor speed
- copy ESC telemetry data into MAVLink telemetry
- save ESC telemetry data in dataflash logs
- use RPM telemetry for dynamic notch filter frequencies
- sum the current telemetry info from all ESCs and use it as virtual battery current monitor sensor
- average the voltage telemetry info and use it as virtual battery voltage monitor sensor
- average the temperature telemetry info and use it as virtual battery temperature monitor sensor
- report telemetry communication error rate in the dataflash logs
- warn the user if there is a gap in the bitmask parameter.
- re-enumerate all ESCs if not armed (motors not spinning) when
  - there is a gap in their address space IDs
  - communication with one of the ESCs is lost
  - some of the configured ESCs are not found
  - some of the configured ESCs are not correctly configured
- allows the user to configure motor rotation direction per ESC (only gets updated if not armed)
- adds a serial simulator of FETtec OneWire ESCs
- adds autotest (using the simulator) to fly a copter over a simulated serial link connection
This commit is contained in:
Dr.-Ing. Amilcar do Carmo Lucas 2021-07-06 21:30:42 +02:00 committed by Peter Barker
parent 38a825c987
commit 1b7b705856
3 changed files with 1335 additions and 887 deletions

File diff suppressed because it is too large Load Diff

View File

@ -14,243 +14,310 @@
*/
/* Initial protocol implementation was provided by FETtec */
/* Strongly modified by Amilcar Lucas, IAV GmbH */
#pragma once
#include <AP_HAL/AP_HAL.h>
#ifndef HAL_AP_FETTECONEWIRE_ENABLED
#define HAL_AP_FETTECONEWIRE_ENABLED !HAL_MINIMIZE_FEATURES
#ifndef HAL_AP_FETTEC_ONEWIRE_ENABLED
#define HAL_AP_FETTEC_ONEWIRE_ENABLED !HAL_MINIMIZE_FEATURES && !defined(HAL_BUILD_AP_PERIPH) && BOARD_FLASH_SIZE > 1024
#endif
#if HAL_AP_FETTECONEWIRE_ENABLED
// Support both full-duplex at 500Kbit/s as well as half-duplex at 2Mbit/s (optional feature)
#ifndef HAL_AP_FETTEC_HALF_DUPLEX
#define HAL_AP_FETTEC_HALF_DUPLEX 0
#endif
// Get static info from the ESCs (optional feature)
#ifndef HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO
#define HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO 0
#endif
// provide beep support (optional feature)
#ifndef HAL_AP_FETTEC_ESC_BEEP
#define HAL_AP_FETTEC_ESC_BEEP 0
#endif
// provide light support (optional feature)
#ifndef HAL_AP_FETTEC_ESC_LIGHT
#define HAL_AP_FETTEC_ESC_LIGHT 0
#endif
#if HAL_AP_FETTEC_ONEWIRE_ENABLED
#include <AP_ESC_Telem/AP_ESC_Telem.h>
#include <AP_Param/AP_Param.h>
class AP_FETtecOneWire : public AP_ESC_Telem_Backend
{
class AP_FETtecOneWire {
public:
AP_FETtecOneWire();
/// Do not allow copies
AP_FETtecOneWire(const AP_FETtecOneWire &other) = delete;
AP_FETtecOneWire &operator=(const AP_FETtecOneWire&) = delete;
static const struct AP_Param::GroupInfo var_info[];
bool pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const;
/// periodically called from SRV_Channels::push()
void update();
static AP_FETtecOneWire *get_singleton() {
return _singleton;
}
#if HAL_AP_FETTEC_ESC_BEEP
/**
makes all connected ESCs beep
@param beep_frequency a 8 bit value from 0-255. higher make a higher beep
*/
void beep(const uint8_t beep_frequency);
#endif
#if HAL_AP_FETTEC_ESC_LIGHT
/**
sets the racewire color for all ESCs
@param r red brightness
@param g green brightness
@param b blue brightness
*/
void led_color(const uint8_t r, const uint8_t g, const uint8_t b);
#endif
private:
void init();
bool initialised;
static AP_FETtecOneWire *_singleton;
AP_HAL::UARTDriver *_uart;
uint32_t last_send_us;
static constexpr uint32_t DELAY_TIME_US = 700;
static constexpr uint8_t DETECT_ESC_COUNT = 4; // TODO needed ?
static constexpr uint8_t MOTOR_COUNT = 4;
uint16_t completeTelemetry[MOTOR_COUNT][5] = {0};
uint16_t motorpwm[MOTOR_COUNT] = {1000};
uint8_t TLM_request = 0;
/*
initialize FETtecOneWire protocol
*/
void FETtecOneWire_Init(void);
/*
deinitialize FETtecOneWire protocol
*/
void FETtecOneWire_DeInit(void);
#if HAL_WITH_ESC_TELEM
static constexpr uint8_t MOTOR_COUNT_MAX = ESC_TELEM_MAX_ESCS; ///< OneWire supports up-to 15 ESCs, but Ardupilot only supports 12
#else
static constexpr uint8_t MOTOR_COUNT_MAX = 12; ///< OneWire supports up-to 15 ESCs, but Ardupilot only supports 12
#endif
AP_Int32 _motor_mask_parameter;
AP_Int32 _reverse_mask_parameter;
#if HAL_WITH_ESC_TELEM
AP_Int8 _pole_count_parameter;
#endif
/*
generates used 8 bit CRC
crc = byte to be added to CRC
crc_seed = CRC where it gets added too
returns 8 bit CRC
*/
uint8_t FETtecOneWire_Update_crc8(uint8_t crc, uint8_t crc_seed);
static constexpr uint8_t FRAME_OVERHEAD = 6;
static constexpr uint8_t MAX_TRANSMIT_LENGTH = 4;
static constexpr uint8_t MAX_RECEIVE_LENGTH = 12;
/*
generates used 8 bit CRC for arrays
Buf = 8 bit byte array
BufLen = count of bytes that should be used for CRC calculation
returns 8 bit CRC
*/
uint8_t FETtecOneWire_Get_crc8(uint8_t *Buf, uint16_t BufLen);
/**
initialize the serial port, scan the OneWire bus, setup the found ESCs
*/
void init();
/*
transmitts a FETtecOneWire frame to a ESC
ESC_id = id of the ESC
Bytes = 8 bit array of bytes. Where byte 1 contains the command, and all following bytes can be the payload
Length = length of the Bytes array
returns nothing
*/
void FETtecOneWire_Transmit(uint8_t ESC_id, uint8_t *Bytes, uint8_t Length);
/**
check if the current configuration is OK
*/
void configuration_check();
/*
reads the answer frame of a ESC
Bytes = 8 bit byte array, where the received answer gets stored in
Length = the expected answer length
returnFullFrame can be OW_RETURN_RESPONSE or OW_RETURN_FULL_FRAME
returns 1 if the expected answer frame was there, 0 if dont
*/
uint8_t FETtecOneWire_Receive(uint8_t *Bytes, uint8_t Length, uint8_t returnFullFrame);
/**
transmits a FETtec OneWire frame to an ESC
@param esc_id id of the ESC
@param bytes 8 bit array of bytes. Where byte 1 contains the command, and all following bytes can be the payload
@param length length of the bytes array
@return false if length is bigger than MAX_TRANSMIT_LENGTH, true on write success
*/
bool transmit(const uint8_t esc_id, const uint8_t *bytes, uint8_t length);
/*
makes all connected ESC's beep
beepFreqency = a 8 bit value from 0-255. higher make a higher beep
*/
void FETtecOneWire_Beep(uint8_t beepFreqency);
/*
sets the racewire color for all ESC's
R, G, B = 8bit colors
*/
void FETtecOneWire_RW_LEDcolor(uint8_t R, uint8_t G, uint8_t B);
/*
Resets a pending pull request
returns nothing
*/
void FETtecOneWire_PullReset(void);
/*
Pulls a complete request between for ESC
ESC_id = id of the ESC
command = 8bit array containing the command that thould be send including the possible payload
response = 8bit array where the response will be stored in
returnFullFrame can be OW_RETURN_RESPONSE or OW_RETURN_FULL_FRAME
returns 1 if the request is completed, 0 if dont
*/
uint8_t FETtecOneWire_PullCommand(uint8_t ESC_id, uint8_t *command, uint8_t *response, uint8_t returnFullFrame);
/*
scans for ESC's in bus. should be called intill FETtecOneWire_ScanActive >= 25
returns the current scanned ID
*/
uint8_t FETtecOneWire_ScanESCs(void);
/*
starts all ESC's in bus and prepares them for receiving teh fast throttle command should be called untill FETtecOneWire_SetupActive >= 25
returns the current used ID
*/
uint8_t FETtecOneWire_InitESCs(void);
/*
checks if the requested telemetry is available.
Telemetry = 16bit array where the read Telemetry will be stored in.
returns the telemetry request number or -1 if unavailable
*/
int8_t FETtecOneWire_CheckForTLM(uint16_t *Telemetry);
/*
does almost all of the job.
scans for ESC's if not already done.
initializes the ESC's if not already done.
sends fast throttle signals if init is complete.
motorValues = a 16bit array containing the throttle signals that should be sent to the motors. 0-2000 where 1001-2000 is positive rotation and 999-0 reversed rotation
Telemetry = 16bit array where the read telemetry will be stored in.
motorCount = the count of motors that should get values send
tlmRequest = the requested telemetry type (OW_TLM_XXXXX)
returns the telemetry request if telemetry was available, -1 if dont
*/
int8_t FETtecOneWire_ESCsSetValues(uint16_t *motorValues, uint16_t *Telemetry, uint8_t motorCount, uint8_t tlmRequest);
uint8_t FETtecOneWire_UpdateCrc8(uint8_t crc, uint8_t crc_seed); //TODO remove
uint8_t FETtecOneWire_GetCrc8(uint8_t* Buf, uint16_t BufLen);
static constexpr uint8_t ALL_ID = 0x1F;
typedef struct FETtecOneWireESC
enum class return_type : uint8_t
{
uint8_t inBootLoader;
uint8_t firmWareVersion;
uint8_t firmWareSubVersion;
uint8_t ESCtype;
uint8_t serialNumber[12];
} FETtecOneWireESC_t;
uint8_t FETtecOneWire_activeESC_IDs[25] = {0};
FETtecOneWireESC_t FETtecOneWire_foundESCs[25];
uint8_t FETtecOneWire_FoundESCs = 0;
uint8_t FETtecOneWire_ScanActive = 0;
uint8_t FETtecOneWire_SetupActive = 0;
uint8_t FETtecOneWire_IgnoreOwnBytes = 0;
int8_t FETtecOneWire_minID = 25;
int8_t FETtecOneWire_maxID = 0;
uint8_t FETtecOneWire_IDcount = 0;
uint8_t FETtecOneWire_FastThrottleByteCount = 0;
uint8_t FETtecOneWire_PullSuccess = 0;
uint8_t FETtecOneWire_PullBusy = 0;
uint8_t FETtecOneWire_TLM_request = 0;
uint8_t FETtecOneWire_lastCRC = 0;
uint8_t FETtecOneWire_firstInitDone = 0;
enum
{
OW_RETURN_RESPONSE,
OW_RETURN_FULL_FRAME
RESPONSE,
FULL_FRAME
};
enum
enum class receive_response : uint8_t
{
OW_OK,
OW_BL_PAGE_CORRECT, // BL only
OW_NOT_OK,
OW_BL_START_FW, // BL only
OW_BL_PAGES_TO_FLASH, // BL only
OW_REQ_TYPE,
OW_REQ_SN,
OW_REQ_SW_VER
NO_ANSWER_YET,
ANSWER_VALID,
CRC_MISSMATCH,
REQ_OVERLENGTH
};
enum
{
OW_RESET_TO_BL = 10,
OW_THROTTLE = 11,
OW_REQ_TLM = 12,
OW_BEEP = 13,
OW_SET_FAST_COM_LENGTH = 26,
OW_GET_ROTATION_DIRECTION = 28,
OW_SET_ROTATION_DIRECTION = 29,
OW_GET_USE_SIN_START = 30,
OW_SET_USE_SIN_START = 31,
OW_GET_3D_MODE = 32,
OW_SET_3D_MODE = 33,
OW_GET_ID = 34,
OW_SET_ID = 35,
/*
OW_GET_LINEAR_THRUST = 36,
OW_SET_LINEAR_THRUST = 37,
*/
OW_GET_EEVER = 38,
OW_GET_PWM_MIN = 39,
OW_SET_PWM_MIN = 40,
OW_GET_PWM_MAX = 41,
OW_SET_PWM_MAX = 42,
OW_GET_ESC_BEEP = 43,
OW_SET_ESC_BEEP = 44,
OW_GET_CURRENT_CALIB = 45,
OW_SET_CURRENT_CALIB = 46,
OW_SET_LED_TMP_COLOR = 51,
OW_GET_LED_COLOR = 52,
OW_SET_LED_COLOR = 53
/**
reads the FETtec OneWire answer frame of an ESC
@param bytes 8 bit byte array, where the received answer gets stored in
@param length the expected answer length
@param return_full_frame can be return_type::RESPONSE or return_type::FULL_FRAME
@return receive_response enum
*/
receive_response receive(uint8_t *bytes, uint8_t length, return_type return_full_frame);
uint8_t receive_buf[FRAME_OVERHEAD + MAX_RECEIVE_LENGTH];
uint8_t receive_buf_used;
void move_preamble_in_receive_buffer(uint8_t search_start_pos = 0);
void consume_bytes(uint8_t n);
enum class pull_state : uint8_t {
BUSY,
COMPLETED,
FAILED
};
enum
/**
Pulls a complete request between flight controller and ESC
@param esc_id id of the ESC
@param command 8bit array containing the command that should be send including the possible payload
@param response 8bit array where the response will be stored in
@param return_full_frame can be return_type::RESPONSE or return_type::FULL_FRAME
@param req_len transmit request length
@return pull_state enum
*/
pull_state pull_command(const uint8_t esc_id, const uint8_t *command, uint8_t *response, return_type return_full_frame, const uint8_t req_len);
/**
Scans for all ESCs in bus. Configures fast-throttle and telemetry for the ones found.
Should be periodically called until _scan.state == scan_state_t::DONE
*/
void scan_escs();
/**
configure the fast-throttle command.
Should be called once after scan_escs() is completted and before config_escs()
*/
void config_fast_throttle();
#if HAL_WITH_ESC_TELEM
/**
increment message packet count for every ESC
*/
void inc_sent_msg_count();
/**
calculates tx (outgoing packets) error-rate by converting the CRC error counts reported by the ESCs into percentage
@param esc_id id of ESC, that the error is calculated for
@param esc_error_count the error count given by the esc
@return the error in percent
*/
float calc_tx_crc_error_perc(const uint8_t esc_id, uint16_t esc_error_count);
/**
if init is complete checks if the requested telemetry is available.
@param t telemetry datastructure where the read telemetry will be stored in.
@param centi_erpm 16bit centi-eRPM value returned from the ESC
@param tx_err_count Ardupilot->ESC communication CRC error counter
@param tlm_from_id receives the ID from the ESC that has respond with its telemetry
@return receive_response enum
*/
receive_response decode_single_esc_telemetry(TelemetryData& t, int16_t& centi_erpm, uint16_t& tx_err_count, uint8_t &tlm_from_id);
#endif
/**
if init is complete sends a single fast-throttle frame containing the throttle for all found OneWire ESCs.
@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 rotation
@param tlm_request the ESC to request telemetry from (-1 for no telemetry, 0 for ESC1, 1 for ESC2, 2 for ESC3, ...)
*/
void escs_set_values(const uint16_t *motor_values, const int8_t tlm_request);
static constexpr uint8_t SERIAL_NR_BITWIDTH = 12;
class FETtecOneWireESC
{
OW_TLM_TEMP,
OW_TLM_VOLT,
OW_TLM_CURRENT,
OW_TLM_ERPM,
OW_TLM_CONSUMPTION,
OW_TLM_DEBUG1,
OW_TLM_DEBUG2,
OW_TLM_DEBUG3
public:
#if HAL_WITH_ESC_TELEM
uint16_t error_count; ///< error counter from the ESCs.
uint16_t error_count_since_overflow; ///< error counter from the ESCs to pass the overflow.
#endif
bool active;
#if HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO
uint8_t firmware_version;
uint8_t firmware_sub_version;
uint8_t esc_type;
uint8_t serial_number[SERIAL_NR_BITWIDTH];
#endif
} _found_escs[MOTOR_COUNT_MAX]; ///< Zero-indexed array
uint32_t _last_config_check_ms;
#if HAL_WITH_ESC_TELEM
float _crc_error_rate_factor; ///< multiply factor. Used to avoid division operations
uint16_t _sent_msg_count; ///< number of fast-throttle commands sent by the flight controller
uint16_t _update_rate_hz;
#endif
uint16_t _motor_mask;
uint16_t _reverse_mask;
uint8_t _nr_escs_in_bitmask; ///< number of ESCs set on the FTW_MASK parameter
uint8_t _found_escs_count; ///< number of ESCs auto-scanned in the bus by the scan_escs() function
uint8_t _configured_escs; ///< number of ESCs fully configured by the scan_escs() function, might be smaller than _found_escs_count
int8_t _requested_telemetry_from_esc; ///< the ESC to request telemetry from (-1 for no telemetry, 0 for ESC1, 1 for ESC2, 2 for ESC3, ...)
#if HAL_AP_FETTEC_HALF_DUPLEX
uint8_t _ignore_own_bytes; ///< bytes to ignore while receiving, because we have transmitted them ourselves
uint8_t _last_crc; ///< the CRC from the last sent fast-throttle command
bool _use_hdplex; ///< use asynchronous half-duplex serial communication
#endif
bool _initialised; ///< device driver and ESCs are fully initialized
bool _pull_busy; ///< request-reply transaction is busy
enum class msg_type : uint8_t
{
OK = 0,
BL_PAGE_CORRECT = 1, ///< Bootloader only
NOT_OK = 2,
BL_START_FW = 3, ///< Bootloader only - exit the boot loader and start the standard firmware
BL_PAGES_TO_FLASH = 4, ///< Bootloader only
#if HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO
REQ_TYPE = 5, ///< ESC type
REQ_SN = 6, ///< serial number
REQ_SW_VER = 7, ///< software version
#endif
#if HAL_AP_FETTEC_ESC_BEEP
BEEP = 13, ///< make noise
#endif
SET_FAST_COM_LENGTH = 26, ///< configure fast-throttle command
SET_TLM_TYPE = 27, ///< telemetry operation mode
SIZEOF_RESPONSE_LENGTH, ///< size of the _response_length array used in the pull_command() function, you can move this one around
#if HAL_AP_FETTEC_ESC_LIGHT
SET_LED_TMP_COLOR = 51, ///< msg_type::SET_LED_TMP_COLOR is ignored here. You must update this if you add new msg_type cases
#endif
};
static uint8_t FETtecOneWire_ResponseLength[54];
static uint8_t FETtecOneWire_RequestLength[54];
enum class scan_state_t : uint8_t {
WAIT_FOR_BOOT, ///< initial state, wait for a ESC(s) cold-start
IN_BOOTLOADER, ///< in bootloader?
START_FW, ///< start the firmware
WAIT_START_FW, ///< wait for the firmware to start
#if HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO
ESC_TYPE, ///< ask the ESC type
SW_VER, ///< ask the software version
SN, ///< ask the serial number
#endif
NEXT_ID, ///< increment ESC ID and jump to IN_BOOTLOADER
CONFIG_FAST_THROTTLE, ///< configure fast-throttle command header
#if HAL_WITH_ESC_TELEM
CONFIG_TLM, ///< configure telemetry mode
#endif
CONFIG_NEXT_ACTIVE_ESC, ///< increment ESC ID and jump to CONFIG_FAST_THROTTLE
DONE ///< configuration done
};
/// presistent scan state data (only used inside scan_escs() function)
struct scan_state
{
uint32_t last_us; ///< last transaction time in microseconds
uint8_t id; ///< Zero-indexed ID of the used ESC
scan_state_t state; ///< scan state-machine state
uint8_t rx_try_cnt; ///< receive try counter
uint8_t trans_try_cnt; ///< transaction (transmit and response) try counter
} _scan;
/// fast-throttle command configuration
struct fast_throttle_config
{
uint16_t bits_to_add_left; ///< bits to add after the header
uint8_t command[4]; ///< fast-throttle command frame header bytes
uint8_t byte_count; ///< nr bytes in a fast throttle command
uint8_t min_id; ///< Zero-indexed ESC ID
uint8_t max_id; ///< Zero-indexed ESC ID
} _fast_throttle;
/// response length lookup table, saves 104 bytes of flash and speeds up the pull_command() function
uint8_t _response_length[uint8_t(msg_type::SIZEOF_RESPONSE_LENGTH)];
};
#endif // HAL_AP_FETTECONEWIRE_ENABLED
#endif // HAL_AP_FETTEC_ONEWIRE_ENABLED

View File

@ -0,0 +1,183 @@
# FETtec OneWire
FETtec OneWire is an [ESC](https://en.wikipedia.org/wiki/Electronic_speed_control) communication protocol created by Felix Niessen (former Flyduino KISS developer) from [FETtec](https://fettec.net).
It is a (bidirectional) [digital full-duplex asynchronous serial communication protocol](https://en.wikipedia.org/wiki/Asynchronous_serial_communication) running at 500Kbit/s Baudrate. It requires three wire (RX, TX and GND) connection (albeit the name OneWire) regardless of the number of ESCs connected.
Unlike bidirectional-Dshot, the FETtec OneWire protocol does not need one DMA channel per ESC for bidirectional communication.
For purchase, connection and configuration information please see the [Ardupilot FETtec OneWire wiki page](https://ardupilot.org/copter/docs/common-fettec-onewire.html).
## Features of this device driver
- use ArduPilot's coding guidelines and naming conventions
- control motor speed
- copy ESC telemetry data into MAVLink telemetry
- save ESC telemetry data in dataflash logs
- use RPM telemetry for dynamic notch filter frequencies
- sum the current telemetry info from all ESCs and use it as virtual battery current monitor sensor
- average the voltage telemetry info and use it as virtual battery voltage monitor sensor
- average the temperature telemetry info and use it as virtual battery temperature monitor sensor
- report telemetry communication error rate in the dataflash logs
- warn the user if there is a gap in the bitmask parameter.
- re-enumerate all ESCs if not armed (motors not spinning) when
- there is a gap in their address space IDs
- communication with one of the ESCs is lost
- some of the configured ESCs are not found
- some of the configured ESCs are not correctly configured
- allows the user to configure motor rotation direction per ESC (only gets updated if not armed)
- adds a serial simulator of FETtec OneWire ESCs
- adds autotest (using the simulator) to fly a copter over a simulated serial link connection
## Ardupilot to ESC protocol
The FETtec OneWire protocol supports up to 24 ESCs. As most copters only use at most 12 motors, Ardupilot's implementation supports only 12 to save memory.
On this device driver the `SERVO_FTW_MASK` parameter must contain a single contiguous block of bits set, and bit0 (zero-indexed) must be a part of that set.
The ESC IDs (one-indexed) set on the ESCs must also be a single contiguous block, but it can start at an ID different from 1. The max ID must be lower than 12.
There are two types of messages sent to the ESCs:
### Configuration message
Consists of six frame bytes + payload bytes.
```
Byte 0 is the transfer direction (e.g. 0x01 Master to Slave)
Byte 1 is the ID
Byte 2 is the frame type (Low byte)
Byte 3 is the frame type (High byte)
Byte 4 is the frame length
Byte 5-254 is the payload
Byte 6-255 is CRC (last Byte after the Payload). It uses the same CRC algorithm as Dshot.
```
### Fast Throttle Signal
```
Byte 0 is the frame header
Byte 1 is the telemetry request and part of fast throttle signal
Byte N is CRC (last Byte after the Payload). It uses the same CRC algorithm as Dshot.
```
The first two bytes are frame header and telemetry request as well as the first parts of the throttle signal.
The following bytes are transmitting the throttle signals for the ESCs (11bit per ESC) followed by the CRC.
The signal is used to transfer the eleven bit throttle signals with as few bytes as possible:
```
[990 .. 0] - negative throttle, rotation in one direction (depends on the motor wiring connection). 980 minimum throttle, 00 maximum throttle
[991 .. 1009] - no rotation, dead-band
[1010 .. 2000] - positive throttle, rotation in the other direction. 1020 minimum throttle, 2000 maximum throttle
```
All motors wait for the complete message with all throttle signals before changing their output.
If telemetry is requested the ESCs will answer them in the ESC-ID order.
See *ESC to Ardupilot Protocol* section below and comments in `FETtecOneWire.cpp` for details.
### Timing
Four ESCs need 90uS for the throttle request and telemetry reception. With four ESCs 11kHz are possible.
As each additional ESC adds 11 extra fast-throttle command bits, so the rate is lowered by each ESC.
If you use 8 ESCs, it needs 160uS including telemetry response, so 5.8kHz are possible.
**Note:** You need at least a 4Hz motor signal (max 250ms between messages) before the motors disarm.
## ESC to Ardupilot protocol
OneWire ESC telemetry information is sent back to the autopilot:
- Electronic rotations per minute (eRPM/100) (must be divided by number of motor poles to translate to propeller RPM)
- Input voltage (V/10)
- Current draw (A/10)
- Power consumption (mAh)
- Temperature (°C/10)
- CRC errors (ArduPilot->ESC) counter
This information is used by Ardupilot to:
- log the status of each ESC to the SDCard or internal Flash, for post flight analysis
- send the status of each ESC to the ground station or companion computer for real-time monitoring
- Optionally dynamically change the center frequency of the notch filters used to reduce frame vibration noise in the gyros
- Optionally measure battery voltage and power consumption
## Full/Alternative Telemetry
The telemetry can be switched to "per ESC" Mode, where one ESC answers with it's full telemetry as oneWire package including CRC and additionally the CRC Errors counted by the ESC.
To use this mode, `msg_type::SET_TLM_TYPE` is send to each ESC while initializing.
If this was successful set the ESC response with `msg_type::OK`.
The answer is packed inside a OneWire package, that can be received with the `FETtecOneWire::receive()` function, that also checks the CRC.
As the packages are send in an uInt8_t array the values must be restored like as only temp is one byte long:
```C++
Telemetry[0]= telem[0]; // Temperature [°C/10]
Telemetry[1]=(telem[1]<<8)|telem[2]; // Voltage [V/10]
Telemetry[2]=(telem[3]<<8)|telem[4]; // Current [A/10]
Telemetry[3]=(telem[5]<<8)|telem[6]; // ERPM/100 (must be divided by number of motor poles to translate to propeller RPM)
Telemetry[4]=(telem[7]<<8)|telem[8]; // Consumption [mA.h]
Telemetry[5]=(telem[9]<<8)|telem[10];// CRC error (ArduPilot->ESC) counter
```
## Extra features
### Read type, firmware version and serial number
To control this you must activate the code in the header file:
```C++
// Get static info from the ESCs (optional feature)
#ifndef HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO
#define HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO 1
#endif
```
Or just set the `HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO` macro in the compiler toolchain.
After that you will be able to access this information in the `_found_escs[]` datastructure.
### Beep
To control this you must activate the code in the header file:
```C++
// provide beep support (optional feature)
#ifndef HAL_AP_FETTEC_ESC_BEEP
#define HAL_AP_FETTEC_ESC_BEEP 1
#endif
```
Or just set the `HAL_AP_FETTEC_ESC_BEEP` macro in the compiler toolchain.
After that you will be able to call the public function:
```C++
/**
makes all connected ESCs beep
@param beep_frequency a 8 bit value from 0-255. higher make a higher beep
*/
void beep(const uint8_t beep_frequency);
```
### Multicolor RGB Led light
To control this you must activate the code in the header file:
```C++
// provide light support (optional feature)
#ifndef HAL_AP_FETTEC_ESC_LIGHT
#define HAL_AP_FETTEC_ESC_LIGHT 1
#endif
```
Or just set the `HAL_AP_FETTEC_ESC_LIGHT` macro in the compiler toolchain.
After that you will be able to call the public function:
```C++
/**
makes all connected ESCs beep
@param beep_frequency a 8 bit value from 0-255. higher make a higher beep
*/
void beep(const uint8_t beep_frequency);
/**
sets the racewire color for all ESCs
@param r red brightness
@param g green brightness
@param b blue brightness
*/
void led_color(const uint8_t r, const uint8_t g, const uint8_t b);
```
You need to call these functions on your own code according to your requirements.