diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp index a78bc87463e56a..23dffa7cef76bb 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp @@ -418,10 +418,19 @@ uint32_t AP_Frsky_SPort_Passthrough::calc_param(void) break; case BATT_CAPACITY_1: param_value = (uint32_t)roundf(AP::battery().pack_capacity_mah(0)); // battery pack capacity in mAh - _paramID = AP::battery().num_instances() > 1 ? BATT_CAPACITY_2 : FRAME_TYPE; + _paramID = AP::battery().num_instances() > 1 ? BATT_CAPACITY_2 : TELEMETRY_FEATURES; break; case BATT_CAPACITY_2: param_value = (uint32_t)roundf(AP::battery().pack_capacity_mah(1)); // battery pack capacity in mAh + _paramID = TELEMETRY_FEATURES; + break; + case TELEMETRY_FEATURES: +#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL + BIT_SET(param_value,PassthroughFeatures::BIDIR); +#endif +#ifdef ENABLE_SCRIPTING + BIT_SET(param_value,PassthroughFeatures::SCRIPTING); +#endif _paramID = FRAME_TYPE; break; } diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.h b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.h index a1ce63c65bf3a5..2b7cd35c47863a 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.h +++ b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.h @@ -91,6 +91,12 @@ class AP_Frsky_SPort_Passthrough : public AP_Frsky_SPort, public AP_RCTelemetry BATT_FS_CAPACITY = 3, BATT_CAPACITY_1 = 4, BATT_CAPACITY_2 = 5, + TELEMETRY_FEATURES = 6 + }; + + enum PassthroughFeatures : uint8_t { + BIDIR = 0, + SCRIPTING = 1, }; // methods to convert flight controller data to FrSky SPort Passthrough (OpenTX) format