delete deprecated BAT_* parameters

This commit is contained in:
Daniel Agar 2020-12-11 21:33:39 -05:00
parent 19bc1f9d02
commit c5b1fe86ca
41 changed files with 76 additions and 407 deletions

View File

@ -126,7 +126,7 @@ then
param set SYS_RESTART_TYPE 2
fi
param set-default BAT_N_CELLS 4
param set-default BAT1_N_CELLS 4
param set-default CBRK_AIRSPD_CHK 0
param set-default CBRK_SUPPLY_CHK 894281

View File

@ -19,7 +19,7 @@
. ${R}etc/init.d/rc.fw_defaults
param set-default BAT_N_CELLS 3
param set-default BAT1_N_CELLS 3
param set-default FW_AIRSPD_MAX 20
param set-default FW_AIRSPD_MIN 12

View File

@ -38,8 +38,9 @@ param set-default MC_YAWRATE_P 0.25
param set-default MC_YAWRATE_I 0.25
param set-default MC_YAWRATE_D 0
param set-default BAT_V_DIV 12.27559
param set-default BAT_A_PER_V 15.39103
param set-default BAT1_V_DIV 12.27559
param set-default BAT1_A_PER_V 15.39103
set MIXER quad_w
set PWM_OUT 1234

View File

@ -26,7 +26,7 @@
. ${R}etc/init.d/rc.mc_defaults
param set-default BAT_N_CELLS 4
param set-default BAT1_N_CELLS 4
param set-default MC_ROLL_P 7
param set-default MC_ROLLRATE_P 0.13

View File

@ -26,8 +26,8 @@
. ${R}etc/init.d/rc.mc_defaults
param set-default BAT_N_CELLS 6
param set-default BAT_V_EMPTY 3.5
param set-default BAT1_N_CELLS 6
param set-default BAT1_V_EMPTY 3.5
param set-default MC_ROLL_P 7
param set-default MC_ROLLRATE_P 0.08
@ -45,6 +45,7 @@ param set-default MC_YAWRATE_D 0
param set-default MPC_XY_VEL_MAX 2
param set-default PWM_MAIN_MIN 1080
set MIXER quad_w
set PWM_OUT 1234

View File

@ -14,7 +14,7 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default BAT_N_CELLS 3
param set-default BAT1_N_CELLS 3
param set-default COM_RC_IN_MODE 1

View File

@ -44,7 +44,8 @@ param set-default MPC_HOLD_MAX_XY 0.25
param set-default MPC_THR_MIN 0.15
param set-default MPC_Z_VEL_MAX_DN 2
param set-default BAT_N_CELLS 4
param set-default BAT1_N_CELLS 4
set MIXER octo_cox_w
set PWM_OUT 12345678

View File

@ -23,9 +23,9 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default BAT_CAPACITY 23000
param set-default BAT_N_CELLS 4
param set-default BAT_R_INTERNAL 0.0025
param set-default BAT1_CAPACITY 23000
param set-default BAT1_N_CELLS 4
param set-default BAT1_R_INTERNAL 0.0025
param set-default CBRK_AIRSPD_CHK 162128
param set-default CBRK_IO_SAFETY 22027

View File

@ -23,8 +23,7 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default BAT_N_CELLS 6
param set-default BAT1_N_CELLS 6
param set-default FW_AIRSPD_MAX 30
param set-default FW_AIRSPD_MIN 19

View File

@ -26,8 +26,8 @@
. ${R}etc/init.d/rc.fw_defaults
param set-default BAT_CAPACITY 2500
param set-default BAT_N_CELLS 3
param set-default BAT1_CAPACITY 2500
param set-default BAT1_N_CELLS 3
param set-default PWM_AUX_RATE 50
param set-default PWM_MAIN_RATE 50
@ -46,5 +46,6 @@ param set-default FW_R_LIM 40
param set-default FW_P_LIM_MAX 25
param set-default FW_P_LIM_MIN -5
param set-default FW_P_RMAX_NEG 20
set MIXER TF-AutoG2
set MIXER_AUX pass

View File

@ -23,7 +23,7 @@
. ${R}etc/init.d/rc.fw_defaults
param set-default BAT_N_CELLS 2
param set-default BAT1_N_CELLS 2
param set-default FW_AIRSPD_MAX 15
param set-default FW_AIRSPD_MIN 10
param set-default FW_AIRSPD_TRIM 13

View File

@ -127,9 +127,9 @@ param set-default IMU_GYRO_CUTOFF 100
param set-default SENS_EN_PMW3901 1
# Power Parameters
param set-default BAT_N_CELLS 4
param set-default BAT_A_PER_V 36.364
param set-default BAT_V_DIV 18.182
param set-default BAT1_N_CELLS 4
param set-default BAT1_A_PER_V 36.364
param set-default BAT1_V_DIV 18.182
# Circuit breakers
param set-default CBRK_IO_SAFETY 22027

View File

@ -54,7 +54,7 @@ param set-default DSHOT_CONFIG 600
param set-default SYS_HAS_BARO 0
param set-default SYS_HAS_MAG 0
param set-default BAT_N_CELLS 2
param set-default BAT1_N_CELLS 2
# The Whoop uses reversed props
set MIXER quad_h
set PWM_OUT 1234

View File

@ -20,7 +20,7 @@ set PWM_OUT 1234
# The set does not include a battery, but most people will probably use 4S
param set-default BAT_N_CELLS 4
param set-default BAT1_N_CELLS 4
param set-default IMU_GYRO_CUTOFF 120
param set-default IMU_DGYRO_CUTOFF 45

View File

@ -17,7 +17,7 @@ set MIXER quad_x
set PWM_OUT 1234
param set-default BAT_N_CELLS 4
param set-default BAT1_N_CELLS 4
param set-default GPS_1_CONFIG 0
param set-default RC_PORT_CONFIG 201

View File

@ -17,7 +17,7 @@ set MIXER quad_x
set PWM_OUT 1234
param set-default BAT_N_CELLS 6
param set-default BAT1_N_CELLS 6
param set-default MC_ROLL_P 6.5
param set-default MC_ROLLRATE_P 0.05

View File

@ -92,10 +92,10 @@ param set-default MPC_TKO_RAMP_T 1
param set-default MPC_TKO_SPEED 1.1
param set-default MPC_VEL_MANUAL 3
param set-default BAT_SOURCE 0
param set-default BAT_N_CELLS 4
param set-default BAT_V_DIV 10.14
param set-default BAT_A_PER_V 18.18
param set-default BAT1_SOURCE 0
param set-default BAT1_N_CELLS 4
param set-default BAT1_V_DIV 10.14
param set-default BAT1_A_PER_V 18.18
#param set CBRK_IO_SAFETY 22027
param set-default COM_DISARM_LAND 2

View File

@ -73,7 +73,7 @@ param set-default PWM_MAIN_RATE 0
param set-default SENS_BOARD_ROT 2
param set-default BAT_SOURCE 0
param set-default BAT1_SOURCE 0
param set-default CBRK_IO_SAFETY 22027
#param set COM_DISARM_LAND 3

View File

@ -102,10 +102,10 @@ param set-default MPC_TKO_RAMP_T 1
param set-default MPC_TKO_SPEED 1.1
param set-default MPC_VEL_MANUAL 3
param set-default BAT_SOURCE 0
param set-default BAT_N_CELLS 4
param set-default BAT_V_DIV 10.14
param set-default BAT_A_PER_V 18.18
param set-default BAT1_SOURCE 0
param set-default BAT1_N_CELLS 4
param set-default BAT1_V_DIV 10.14
param set-default BAT1_A_PER_V 18.18
#param set CBRK_IO_SAFETY 22027
param set-default COM_DISARM_LAND 2

View File

@ -21,7 +21,7 @@ set MIXER quad_x
set PWM_OUT 1234
param set-default BAT_N_CELLS 1
param set-default BAT1_N_CELLS 1
param set-default MC_ROLL_P 8
param set-default MC_ROLLRATE_P 0.19

View File

@ -32,17 +32,18 @@ set PWM_OUT 1234
param reset_all SYS_AUTOSTART SYS_AUTOCONFIG RC* COM_FLTMODE* LND_FLIGHT_T_* TC_* CAL_ACC* CAL_GYRO* CAL_MAG* SENS_BOARD* EKF2_MAGBIAS*
# battery
param set-default BAT_CAPACITY 2750
param set-default BAT_CRIT_THR 0.15
param set-default BAT_EMERGEN_THR 0.075
param set-default BAT_LOW_THR 0.20
param set-default BAT_N_CELLS 4
param set-default BAT_R_INTERNAL 0.06
param set-default BAT_SOURCE 1
param set-default BAT_V_CHARGED 4.15
param set-default BAT_V_DIV 11.1625
param set-default BAT_V_EMPTY 3.65
param set-default BAT_V_OFFS_CURR -0.0045
param set-default BAT1_CAPACITY 2750
param set-default BAT1_N_CELLS 4
param set-default BAT1_R_INTERNAL 0.06
param set-default BAT1_SOURCE 1
param set-default BAT1_V_CHARGED 4.15
param set-default BAT1_V_DIV 11.1625
param set-default BAT1_V_EMPTY 3.65
param set-default BAT1_V_OFFS_CURR -0.0045
# sensor calibration
param set-default CAL_MAG_SIDES 63

View File

@ -19,9 +19,9 @@
set MIXER quad_x_cw
set PWM_OUT 1234
param set-default BAT_N_CELLS 1
param set-default BAT_CAPACITY 240
param set-default BAT_SOURCE 1
param set-default BAT1_N_CELLS 1
param set-default BAT1_CAPACITY 240
param set-default BAT1_SOURCE 1
param set-default CBRK_SUPPLY_CHK 894281
param set-default CBRK_USB_CHK 197848

View File

@ -16,7 +16,7 @@
. ${R}etc/init.d/rc.rover_defaults
param set-default BAT_N_CELLS 2
param set-default BAT1_N_CELLS 2
param set-default EKF2_ANGERR_INIT 0.01
param set-default EKF2_GBIAS_INIT 0.01

View File

@ -19,7 +19,7 @@
. ${R}etc/init.d/rc.rover_defaults
param set-default BAT_N_CELLS 4
param set-default BAT1_N_CELLS 4
param set-default EKF2_GBIAS_INIT 0.01
param set-default EKF2_ANGERR_INIT 0.01

View File

@ -21,7 +21,7 @@
. ${R}etc/init.d/rc.rover_defaults
param set-default BAT_N_CELLS 2
param set-default BAT1_N_CELLS 2
param set-default EKF2_GBIAS_INIT 0.01
param set-default EKF2_ANGERR_INIT 0.01

View File

@ -116,9 +116,9 @@ param set-default COM_DISARM_LAND 3
param set-default PWM_MAIN_RATE 0
# Battery
param set-default BAT_SOURCE 0
param set-default BAT_N_CELLS 4
param set-default BAT_V_DIV 10.133
param set-default BAT1_SOURCE 0
param set-default BAT1_N_CELLS 4
param set-default BAT1_V_DIV 10.133
# TELEM1 ttyS1
param set-default MAV_0_CONFIG 101

View File

@ -6,11 +6,9 @@
# Enables the 2nd bank of mixers
set AUX_BANK2 yes
param set-default BAT_V_DIV 18
param set-default BAT1_V_DIV 18
param set-default BAT2_V_DIV 18
param set-default BAT_A_PER_V 24
param set-default BAT1_A_PER_V 24
param set-default BAT2_A_PER_V 24

View File

@ -6,11 +6,9 @@
# Enables the 2nd bank of mixers
set AUX_BANK2 yes
param set-default BAT_V_DIV 18
param set-default BAT1_V_DIV 18
param set-default BAT2_V_DIV 18
param set-default BAT_A_PER_V 24
param set-default BAT1_A_PER_V 24
param set-default BAT2_A_PER_V 24

View File

@ -3,12 +3,9 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT_V_DIV 10.1
param set-default BAT1_V_DIV 10.1
param set-default BAT2_V_DIV 10.1
param set-default BAT_A_PER_V 17
param set-default BAT1_A_PER_V 17
param set-default BAT2_A_PER_V 17

View File

@ -4,11 +4,9 @@
#------------------------------------------------------------------------------
param set-default BAT_V_DIV 10.1
param set-default BAT1_V_DIV 10.1
param set-default BAT2_V_DIV 10.1
param set-default BAT_A_PER_V 17
param set-default BAT1_A_PER_V 17
param set-default BAT2_A_PER_V 17

View File

@ -5,7 +5,7 @@
param load
param set BAT_N_CELLS 3
param set BAT1_N_CELLS 3
param set CBRK_SUPPLY_CHK 894281
param set MAV_TYPE 22
param set VT_TYPE 2

View File

@ -41,7 +41,7 @@ param set MAV_TYPE 2
param set BAT1_V_CHANNEL 5
# Battery voltage scale factor, from BBBlue schematics: (4.7K + 47K) / 4.7K = 11
param set BAT_V_DIV 11.0
param set BAT1_V_DIV 11.0
dataman start

View File

@ -41,7 +41,7 @@ param set MAV_TYPE 2
param set BAT1_V_CHANNEL 5
# Battery voltage scale factor, from BBBlue schematics: (4.7K + 47K) / 4.7K = 11
param set BAT_V_DIV 11.0
param set BAT1_V_DIV 11.0
dataman start

View File

@ -54,8 +54,8 @@ BATT_SMBUS::BATT_SMBUS(const I2CSPIDriverConfig &config, SMBus *interface) :
int32_t battsource = 1;
int32_t batt_device_type = static_cast<int32_t>(SMBUS_DEVICE_TYPE::UNDEFINED);
param_set(param_find("BAT_SOURCE"), &battsource);
param_get(param_find("BAT_SMBUS_MODEL"), &batt_device_type);
param_set(param_find("BAT1_SOURCE"), &battsource);
param_get(param_find("BAT1_SMBUS_MODEL"), &batt_device_type);
//TODO: probe the device and autodetect its type
@ -84,7 +84,7 @@ BATT_SMBUS::~BATT_SMBUS()
}
int32_t battsource = 0;
param_set(param_find("BAT_SOURCE"), &battsource);
param_set(param_find("BAT1_SOURCE"), &battsource);
}
void BATT_SMBUS::RunImpl()
@ -359,13 +359,14 @@ int BATT_SMBUS::get_startup_info()
int ret = PX4_OK;
// Read battery threshold params on startup.
// TODO: support instances
param_get(param_find("BAT_CRIT_THR"), &_crit_thr);
param_get(param_find("BAT_LOW_THR"), &_low_thr);
param_get(param_find("BAT_EMERGEN_THR"), &_emergency_thr);
param_get(param_find("BAT_C_MULT"), &_c_mult);
param_get(param_find("BAT1_C_MULT"), &_c_mult);
int32_t cell_count_param = 0;
param_get(param_find("BAT_N_CELLS"), &cell_count_param);
param_get(param_find("BAT1_N_CELLS"), &cell_count_param);
_cell_count = math::min((uint8_t)cell_count_param, MAX_NUM_OF_CELLS);
ret |= _interface->block_read(BATT_SMBUS_MANUFACTURER_NAME, _manufacturer_name, BATT_SMBUS_MANUFACTURER_NAME_SIZE,

View File

@ -48,7 +48,7 @@ PARAM_DEFINE_INT32(SENS_EN_BATT, 0);
* @decimal 1
* @group Sensors
*/
PARAM_DEFINE_FLOAT(BAT_C_MULT, 1.0f);
PARAM_DEFINE_FLOAT(BAT1_C_MULT, 1.0f);
/**
* Battery device model
@ -61,4 +61,4 @@ PARAM_DEFINE_FLOAT(BAT_C_MULT, 1.0f);
* @value 1 BQ40Z50 based
* @value 2 BQ40Z80 based
*/
PARAM_DEFINE_INT32(BAT_SMBUS_MODEL, 0);
PARAM_DEFINE_INT32(BAT1_SMBUS_MODEL, 0);

View File

@ -92,14 +92,6 @@ Battery::Battery(int index, ModuleParams *parent, const int sample_interval_us)
_param_handles.crit_thr = param_find("BAT_CRIT_THR");
_param_handles.emergen_thr = param_find("BAT_EMERGEN_THR");
_param_handles.v_empty_old = param_find("BAT_V_EMPTY");
_param_handles.v_charged_old = param_find("BAT_V_CHARGED");
_param_handles.n_cells_old = param_find("BAT_N_CELLS");
_param_handles.capacity_old = param_find("BAT_CAPACITY");
_param_handles.v_load_drop_old = param_find("BAT_V_LOAD_DROP");
_param_handles.r_internal_old = param_find("BAT_R_INTERNAL");
_param_handles.source_old = param_find("BAT_SOURCE");
updateParams();
}
@ -255,32 +247,13 @@ void Battery::computeScale()
void Battery::updateParams()
{
if (_index == 1) {
migrateParam<float>(_param_handles.v_empty_old, _param_handles.v_empty, &_params.v_empty_old, &_params.v_empty,
_first_parameter_update);
migrateParam<float>(_param_handles.v_charged_old, _param_handles.v_charged, &_params.v_charged_old, &_params.v_charged,
_first_parameter_update);
migrateParam<int32_t>(_param_handles.n_cells_old, _param_handles.n_cells, &_params.n_cells_old, &_params.n_cells,
_first_parameter_update);
migrateParam<float>(_param_handles.capacity_old, _param_handles.capacity, &_params.capacity_old, &_params.capacity,
_first_parameter_update);
migrateParam<float>(_param_handles.v_load_drop_old, _param_handles.v_load_drop, &_params.v_load_drop_old,
&_params.v_load_drop, _first_parameter_update);
migrateParam<float>(_param_handles.r_internal_old, _param_handles.r_internal, &_params.r_internal_old,
&_params.r_internal, _first_parameter_update);
migrateParam<int32_t>(_param_handles.source_old, _param_handles.source, &_params.source_old, &_params.source,
_first_parameter_update);
} else {
param_get(_param_handles.v_empty, &_params.v_empty);
param_get(_param_handles.v_charged, &_params.v_charged);
param_get(_param_handles.n_cells, &_params.n_cells);
param_get(_param_handles.capacity, &_params.capacity);
param_get(_param_handles.v_load_drop, &_params.v_load_drop);
param_get(_param_handles.r_internal, &_params.r_internal);
param_get(_param_handles.source, &_params.source);
}
param_get(_param_handles.v_empty, &_params.v_empty);
param_get(_param_handles.v_charged, &_params.v_charged);
param_get(_param_handles.n_cells, &_params.n_cells);
param_get(_param_handles.capacity, &_params.capacity);
param_get(_param_handles.v_load_drop, &_params.v_load_drop);
param_get(_param_handles.r_internal, &_params.r_internal);
param_get(_param_handles.source, &_params.source);
param_get(_param_handles.low_thr, &_params.low_thr);
param_get(_param_handles.crit_thr, &_params.crit_thr);
param_get(_param_handles.emergen_thr, &_params.emergen_thr);

View File

@ -108,16 +108,6 @@ protected:
param_t crit_thr;
param_t emergen_thr;
param_t source;
// TODO: These parameters are depracated. They can be removed entirely once the
// new version of Firmware has been around for long enough.
param_t v_empty_old;
param_t v_charged_old;
param_t n_cells_old;
param_t capacity_old;
param_t v_load_drop_old;
param_t r_internal_old;
param_t source_old;
} _param_handles{};
struct {
@ -131,16 +121,6 @@ protected:
float crit_thr;
float emergen_thr;
int32_t source;
// TODO: These parameters are depracated. They can be removed entirely once the
// new version of Firmware has been around for long enough.
float v_empty_old;
float v_charged_old;
int32_t n_cells_old;
float capacity_old;
float v_load_drop_old;
float r_internal_old;
int32_t source_old;
} _params{};
const int _index;
@ -148,40 +128,6 @@ protected:
bool _first_parameter_update{true};
void updateParams() override;
/**
* This function helps migrating and syncing from/to deprecated parameters. BAT_* BAT1_*
* @tparam T Type of the parameter (int or float)
* @param old_param Handle to the old deprecated parameter (for example, param_find("BAT_N_CELLS"))
* @param new_param Handle to the new replacement parameter (for example, param_find("BAT1_N_CELLS"))
* @param old_val Pointer to the value of the old deprecated parameter
* @param new_val Pointer to the value of the new replacement parameter
* @param firstcall If true, this function prefers migrating old to new
*/
template<typename T>
void migrateParam(param_t old_param, param_t new_param, T *old_val, T *new_val, bool firstcall)
{
T previous_old_val = *old_val;
T previous_new_val = *new_val;
// Update both the old and new parameter values
param_get(old_param, old_val);
param_get(new_param, new_val);
// Check if the parameter values are different
if (!matrix::isEqualF((float)*old_val, (float)*new_val)) {
// If so, copy the new value over to the unchanged parameter
// Note: If they differ from the beginning we migrate old to new
if (firstcall || !matrix::isEqualF((float)*old_val, (float)previous_old_val)) {
param_set_no_notification(new_param, old_val);
param_get(new_param, new_val);
} else if (!matrix::isEqualF((float)*new_val, (float)previous_new_val)) {
param_set_no_notification(old_param, new_val);
param_get(old_param, old_val);
}
}
}
private:
void sumDischarged(const hrt_abstime &timestamp, float current_a);
void estimateStateOfCharge(const float voltage_v, const float current_a, const float throttle);

View File

@ -1,163 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2012-2019 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file battery_params_deprecated.c
* @author Timothy Scott <timothy@auterion.com>
*
* Defines the deprcated single battery configuration which are temporarily kept for backwards compatibility with QGC.
* The new parameter set has a number after "BAT" e.g. BAT1_V_EMPTY.
*/
/**
* This parameter is deprecated. Please use BAT1_V_EMPTY instead.
*
* Defines the voltage where a single cell of battery 1 is considered empty.
* The voltage should be chosen before the steep dropoff to 2.8V. A typical
* lithium battery can only be discharged down to 10% before it drops off
* to a voltage level damaging the cells.
*
* @group Battery Calibration
* @unit V
* @decimal 2
* @increment 0.01
* @reboot_required true
*/
PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.5f);
/**
* This parameter is deprecated. Please use BAT1_V_CHARGED instead.
*
* Defines the voltage where a single cell of battery 1 is considered full
* under a mild load. This will never be the nominal voltage of 4.2V
*
* @group Battery Calibration
* @unit V
* @decimal 2
* @increment 0.01
* @reboot_required true
*/
PARAM_DEFINE_FLOAT(BAT_V_CHARGED, 4.05f);
/**
* This parameter is deprecated. Please use BAT1_V_LOAD_DROP instead.
*
* This implicitely defines the internal resistance
* to maximum current ratio for battery 1 and assumes linearity.
* A good value to use is the difference between the
* 5C and 20-25C load. Not used if BAT_R_INTERNAL is
* set.
*
* @group Battery Calibration
* @unit V
* @min 0.07
* @max 0.5
* @decimal 2
* @increment 0.01
* @reboot_required true
*/
PARAM_DEFINE_FLOAT(BAT_V_LOAD_DROP, 0.3f);
/**
* This parameter is deprecated. Please use BAT1_R_INTERNAL instead.
*
* If non-negative, then this will be used in place of
* BAT_V_LOAD_DROP for all calculations.
*
* @group Battery Calibration
* @unit Ohm
* @min -1.0
* @max 0.2
* @reboot_required true
*/
PARAM_DEFINE_FLOAT(BAT_R_INTERNAL, -1.0f);
/**
* This parameter is deprecated. Please use BAT1_N_CELLS instead.
*
* Defines the number of cells the attached battery consists of.
*
* @group Battery Calibration
* @unit S
* @value 0 Unconfigured
* @value 2 2S Battery
* @value 3 3S Battery
* @value 4 4S Battery
* @value 5 5S Battery
* @value 6 6S Battery
* @value 7 7S Battery
* @value 8 8S Battery
* @value 9 9S Battery
* @value 10 10S Battery
* @value 11 11S Battery
* @value 12 12S Battery
* @value 13 13S Battery
* @value 14 14S Battery
* @value 15 15S Battery
* @value 16 16S Battery
* @reboot_required true
*/
PARAM_DEFINE_INT32(BAT_N_CELLS, 0);
/**
* This parameter is deprecated. Please use BAT1_CAPACITY instead.
*
* Defines the capacity of battery 1.
*
* @group Battery Calibration
* @unit mAh
* @decimal 0
* @min -1.0
* @max 100000
* @increment 50
* @reboot_required true
*/
PARAM_DEFINE_FLOAT(BAT_CAPACITY, -1.0f);
/**
* This parameter is deprecated. Please use BAT1_SOURCE instead.
*
* Battery monitoring source.
*
* This parameter controls the source of battery data. The value 'Power Module'
* means that measurements are expected to come from a power module. If the value is set to
* 'External' then the system expects to receive mavlink battery status messages.
*
* @min 0
* @max 1
* @value 0 Power Module
* @value 1 External
* @group Battery Calibration
*/
PARAM_DEFINE_INT32(BAT_SOURCE, 0);

View File

@ -67,10 +67,6 @@ AnalogBattery::AnalogBattery(int index, ModuleParams *parent, const int sample_i
snprintf(param_name, sizeof(param_name), "BAT%d_I_CHANNEL", index);
_analog_param_handles.i_channel = param_find(param_name);
_analog_param_handles.v_div_old = param_find("BAT_V_DIV");
_analog_param_handles.a_per_v_old = param_find("BAT_A_PER_V");
_analog_param_handles.adc_channel_old = param_find("BAT_ADC_CHANNEL");
}
void
@ -119,24 +115,12 @@ int AnalogBattery::get_current_channel()
}
}
void
AnalogBattery::updateParams()
{
if (_index == 1) {
migrateParam<float>(_analog_param_handles.v_div_old, _analog_param_handles.v_div, &_analog_params.v_div_old,
&_analog_params.v_div, _first_parameter_update);
migrateParam<float>(_analog_param_handles.a_per_v_old, _analog_param_handles.a_per_v, &_analog_params.a_per_v_old,
&_analog_params.a_per_v, _first_parameter_update);
migrateParam<int32_t>(_analog_param_handles.adc_channel_old, _analog_param_handles.v_channel,
&_analog_params.adc_channel_old, &_analog_params.v_channel, _first_parameter_update);
} else {
param_get(_analog_param_handles.v_div, &_analog_params.v_div);
param_get(_analog_param_handles.a_per_v, &_analog_params.a_per_v);
param_get(_analog_param_handles.v_channel, &_analog_params.v_channel);
}
param_get(_analog_param_handles.v_div, &_analog_params.v_div);
param_get(_analog_param_handles.a_per_v, &_analog_params.a_per_v);
param_get(_analog_param_handles.v_channel, &_analog_params.v_channel);
param_get(_analog_param_handles.i_channel, &_analog_params.i_channel);
param_get(_analog_param_handles.v_offs_cur, &_analog_params.v_offs_cur);
@ -144,23 +128,12 @@ AnalogBattery::updateParams()
/* apply scaling according to defaults if set to default */
_analog_params.v_div = BOARD_BATTERY1_V_DIV;
param_set_no_notification(_analog_param_handles.v_div, &_analog_params.v_div);
if (_index == 1) {
_analog_params.v_div_old = BOARD_BATTERY1_V_DIV;
param_set_no_notification(_analog_param_handles.v_div_old, &_analog_params.v_div_old);
}
}
if (_analog_params.a_per_v < 0.0f) {
/* apply scaling according to defaults if set to default */
_analog_params.a_per_v = BOARD_BATTERY1_A_PER_V;
param_set_no_notification(_analog_param_handles.a_per_v, &_analog_params.a_per_v);
if (_index == 1) {
_analog_params.a_per_v_old = BOARD_BATTERY1_A_PER_V;
param_set_no_notification(_analog_param_handles.a_per_v_old, &_analog_params.a_per_v_old);
}
}
Battery::updateParams();

View File

@ -78,10 +78,6 @@ protected:
param_t a_per_v;
param_t v_channel;
param_t i_channel;
param_t v_div_old;
param_t a_per_v_old;
param_t adc_channel_old;
} _analog_param_handles;
struct {
@ -90,10 +86,6 @@ protected:
float a_per_v;
int32_t v_channel;
int32_t i_channel;
float v_div_old;
float a_per_v_old;
int32_t adc_channel_old;
} _analog_params;
virtual void updateParams() override;

View File

@ -1,48 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2012-2019 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* This parameter is deprecated. Please use BAT1_V_DIV.
*
* @group Battery Calibration
* @decimal 8
*/
PARAM_DEFINE_FLOAT(BAT_V_DIV, -1.0);
/**
* This parameter is deprecated. Please use BAT1_A_PER_V.
*
* @group Battery Calibration
* @decimal 8
*/
PARAM_DEFINE_FLOAT(BAT_A_PER_V, -1.0);