AP_Frsky_Telem: add second battery capacity parameter

This commit is contained in:
Florent Martel 2017-10-10 08:41:05 -05:00 committed by Tom Pittenger
parent 191e457230
commit 5d9299d72f
2 changed files with 11 additions and 5 deletions

View File

@ -567,13 +567,13 @@ uint32_t AP_Frsky_Telem::calc_param(void)
uint32_t param = 0;
// cycle through paramIDs
if (_paramID >= 4) {
if (_paramID >= 5) {
_paramID = 0;
}
_paramID++;
switch(_paramID) {
case 1:
param = _params.mav_type; // frame type (see MAV_TYPE in Mavlink definition file common.h)
param = _params.mav_type; // frame type (see MAV_TYPE in Mavlink definition file common.h)
break;
case 2:
if (_params.fs_batt_voltage != nullptr) {
@ -582,15 +582,18 @@ uint32_t AP_Frsky_Telem::calc_param(void)
break;
case 3:
if (_params.fs_batt_mah != nullptr) {
param = (uint32_t)roundf((*_params.fs_batt_mah)); // battery failsafe capacity in mAh
param = (uint32_t)roundf((*_params.fs_batt_mah)); // battery failsafe capacity in mAh
}
break;
case 4:
param = (uint32_t)roundf(_battery.pack_capacity_mah()); // battery pack capacity in mAh as configured by user
param = (uint32_t)roundf(_battery.pack_capacity_mah(0)); // battery pack capacity in mAh
break;
case 5:
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 << 24) | (param & 0xFFFFFF);
param = (_paramID << PARAM_ID_OFFSET) | (param & PARAM_VALUE_LIMIT);
return param;
}

View File

@ -71,6 +71,9 @@ for FrSky SPort and SPort Passthrough (OpenTX) protocols (X-receivers)
for FrSky SPort Passthrough
*/
// data bits preparation
// for parameter data
#define PARAM_ID_OFFSET 24
#define PARAM_VALUE_LIMIT 0xFFFFFF
// for gps status data
#define GPS_SATS_LIMIT 0xF
#define GPS_STATUS_LIMIT 0x3