AP_Frsky_Telem: Remove unneeded battery failsafe parameters

This commit is contained in:
Michael du Breuil 2018-01-11 16:39:39 -07:00 committed by Francisco Ferreira
parent 4a11093ebb
commit 3f581d0479
2 changed files with 4 additions and 15 deletions

View File

@ -36,7 +36,7 @@ AP_Frsky_Telem::AP_Frsky_Telem(AP_AHRS &ahrs, const AP_BattMonitor &battery, con
/*
* init - perform required initialisation
*/
void AP_Frsky_Telem::init(const AP_SerialManager &serial_manager, const char *firmware_str, const uint8_t mav_type, const AP_Float *fs_batt_voltage, const AP_Float *fs_batt_mah, const uint32_t *ap_valuep)
void AP_Frsky_Telem::init(const AP_SerialManager &serial_manager, const char *firmware_str, const uint8_t mav_type, const uint32_t *ap_valuep)
{
// check for protocol configured for a serial port - only the first serial port with one of these protocols will then run (cannot have FrSky on multiple serial ports)
if ((_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_D, 0))) {
@ -51,8 +51,6 @@ void AP_Frsky_Telem::init(const AP_SerialManager &serial_manager, const char *fi
queue_message(MAV_SEVERITY_INFO, firmware_str);
// save main parameters locally
_params.mav_type = mav_type; // frame type (see MAV_TYPE in Mavlink definition file common.h)
_params.fs_batt_voltage = fs_batt_voltage; // failsafe battery voltage in volts
_params.fs_batt_mah = fs_batt_mah; // failsafe reserve capacity in mAh
if (ap_valuep == nullptr) { // ap bit-field
_ap.value = 0x2000; // set "initialised" to 1 for rover and plane
_ap.valuep = &_ap.value;
@ -582,15 +580,8 @@ uint32_t AP_Frsky_Telem::calc_param(void)
case 1:
param = _params.mav_type; // frame type (see MAV_TYPE in Mavlink definition file common.h)
break;
case 2:
if (_params.fs_batt_voltage != nullptr) {
param = (uint32_t)roundf((*_params.fs_batt_voltage) * 100.0f); // battery failsafe voltage in centivolts
}
break;
case 3:
if (_params.fs_batt_mah != nullptr) {
param = (uint32_t)roundf((*_params.fs_batt_mah)); // battery failsafe capacity in mAh
}
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:
param = (uint32_t)roundf(_battery.pack_capacity_mah(0)); // battery pack capacity in mAh

View File

@ -120,7 +120,7 @@ public:
AP_Frsky_Telem &operator=(const AP_Frsky_Telem&) = delete;
// init - perform required initialisation
void init(const AP_SerialManager &serial_manager, const char *firmware_str, const uint8_t mav_type, const AP_Float *fs_batt_voltage = nullptr, const AP_Float *fs_batt_mah = nullptr, const uint32_t *ap_valuep = nullptr);
void init(const AP_SerialManager &serial_manager, const char *firmware_str, const uint8_t mav_type, const uint32_t *ap_valuep = nullptr);
// add statustext message to FrSky lib message queue
void queue_message(MAV_SEVERITY severity, const char *text);
@ -153,8 +153,6 @@ private:
struct
{
uint8_t mav_type; // frame type (see MAV_TYPE in Mavlink definition file common.h)
const AP_Float *fs_batt_voltage; // failsafe battery voltage in volts
const AP_Float *fs_batt_mah; // failsafe reserve capacity in mAh
} _params;
struct