mirror of https://github.com/ArduPilot/ardupilot
AP_Frsky_Telem: added new capabilities param to frame 0x5007
This commit is contained in:
parent
592fba7416
commit
b62c2d9518
|
@ -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;
|
||||
}
|
||||
|
|
|
@ -91,6 +91,12 @@ private:
|
|||
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
|
||||
|
|
Loading…
Reference in New Issue