diff --git a/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp b/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp index 088a884247..200651a446 100644 --- a/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp +++ b/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp @@ -122,12 +122,13 @@ void AP_FETtecOneWire::init() _motor_mask = uint32_t(_motor_mask_parameter); // take a copy that will not change after we leave this function _esc_count = __builtin_popcount(_motor_mask); #if HAL_WITH_ESC_TELEM - // OneWire supports at most 15 ESCs, because of the 4 bit limitation + // OneWire supports telemetry in at most 15 ESCs, because of the 4 bit limitation // on the fast-throttle command. But we are still limited to the // number of ESCs the telem library will collect data for. - if (_esc_count == 0 || _motor_mask >= (1U << MIN(15,ESC_TELEM_MAX_ESCS))) { + if (_esc_count == 0 || _motor_mask >= (1U << MIN(15, ESC_TELEM_MAX_ESCS))) { #else - if (_esc_count == 0 || _motor_mask >= (1U << MIN(15,NUM_SERVO_CHANNELS))) { + // OneWire supports at most 24 ESCs without telemetry + if (_esc_count == 0 || _motor_mask >= (1U << MIN(24, NUM_SERVO_CHANNELS))) { #endif _invalid_mask = true; return; diff --git a/libraries/AP_FETtecOneWire/README.md b/libraries/AP_FETtecOneWire/README.md index c25566a9d8..482670b0fb 100644 --- a/libraries/AP_FETtecOneWire/README.md +++ b/libraries/AP_FETtecOneWire/README.md @@ -41,7 +41,7 @@ For purchase, connection and configuration information please see the [ArduPilot ## 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 (`ESC_TELEM_MAX_ESCS`)to save memory. +The FETtec OneWire protocol supports up to 24 ESCs without telemetry and up to 15 ESCs with telemetry. There are two types of messages sent to the ESCs configuration and fast-throttle messages: @@ -165,7 +165,7 @@ pre_arm_check() The `SERVO_FTW_MASK` parameter selects which servo outputs, if any, will be routed to FETtec ESCs. You need to reboot after changing this parameter. -When `HAL_WITH_ESC_TELEM` is active (default) only the first 12 (`ESC_TELEM_MAX_ESCS`) can be used. +When `HAL_WITH_ESC_TELEM` is active (default) only the first 15 (`ESC_TELEM_MAX_ESCS`) can be used. The FETtec ESC IDs set inside the FETtec firmware by the FETtec configuration tool are one-indexed. These IDs must start at ID 1 and be in a single contiguous block. You do not need to change these FETtec IDs if you change the servo output assignments inside ArduPilot the using the `SERVO_FTW_MASK` parameter.