From 683df64d86ade3a4cf036e6bd14e403d272949a6 Mon Sep 17 00:00:00 2001 From: yaapu Date: Sun, 19 Jul 2020 22:47:29 +0200 Subject: [PATCH] AP_Frsky_Telem: fix frsky serial 10 parameters param rotation now is frame_type, battery_1, battery_2 (only if present) --- libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp | 18 ++++++++++-------- libraries/AP_Frsky_Telem/AP_Frsky_Telem.h | 8 ++++++++ 2 files changed, 18 insertions(+), 8 deletions(-) diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp index b95b065f01..905833711c 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp @@ -583,29 +583,31 @@ uint32_t AP_Frsky_Telem::calc_param(void) const AP_BattMonitor &_battery = AP::battery(); uint32_t param = 0; + uint8_t last_param = AP::battery().num_instances() > 1 ? BATT_CAPACITY_2 : BATT_CAPACITY_1; // cycle through paramIDs - if (_paramID >= 5) { + if (_paramID >= last_param) { _paramID = 0; } + _paramID++; switch(_paramID) { - case 1: + case FRAME_TYPE: param = gcs().frame_type(); // see MAV_TYPE in Mavlink definition file common.h break; - case 2: // was used to send the battery failsafe voltage - case 3: // was used to send the battery failsafe capacity in mAh - break; - case 4: + case BATT_FS_VOLTAGE: // was used to send the battery failsafe voltage, lend slot to next param + case BATT_FS_CAPACITY: // was used to send the battery failsafe capacity in mAh, lend slot to next param + case BATT_CAPACITY_1: + _paramID = 4; param = (uint32_t)roundf(_battery.pack_capacity_mah(0)); // battery pack capacity in mAh break; - case 5: + case BATT_CAPACITY_2: param = (uint32_t)roundf(_battery.pack_capacity_mah(1)); // battery pack capacity in mAh break; } //Reserve first 8 bits for param ID, use other 24 bits to store parameter value param = (_paramID << PARAM_ID_OFFSET) | (param & PARAM_VALUE_LIMIT); - + return param; } diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.h b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.h index eb23b20620..0f7070956d 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.h +++ b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.h @@ -155,6 +155,14 @@ private: PARAM = 10 // 0x5007 parameters }; + enum PassthroughParam : uint8_t { + FRAME_TYPE = 1, + BATT_FS_VOLTAGE = 2, + BATT_FS_CAPACITY = 3, + BATT_CAPACITY_1 = 4, + BATT_CAPACITY_2 = 5 + }; + struct { int32_t vario_vspd;