2015-08-11 03:28:42 -03:00
# include <AP_HAL/AP_HAL.h>
# include <AP_Common/AP_Common.h>
# include <AP_Math/AP_Math.h>
2014-12-04 01:35:31 -04:00
# include "AP_BattMonitor_Analog.h"
extern const AP_HAL : : HAL & hal ;
2021-06-24 02:38:19 -03:00
const AP_Param : : GroupInfo AP_BattMonitor_Analog : : var_info [ ] = {
// @Param: VOLT_PIN
// @DisplayName: Battery Voltage sensing pin
// @Description: Sets the analog input pin that should be used for voltage monitoring.
// @Values: -1:Disabled, 2:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 5:Navigator, 13:Pixhawk2_PM2/CubeOrange_PM2, 14:CubeOrange, 16:Durandal, 100:PX4-v1
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " VOLT_PIN " , 1 , AP_BattMonitor_Analog , _volt_pin , AP_BATT_VOLT_PIN ) ,
// @Param: CURR_PIN
// @DisplayName: Battery Current sensing pin
// @Description: Sets the analog input pin that should be used for current monitoring.
// @Values: -1:Disabled, 3:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 4:CubeOrange_PM2/Navigator, 14:Pixhawk2_PM2, 15:CubeOrange, 17:Durandal, 101:PX4-v1
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " CURR_PIN " , 2 , AP_BattMonitor_Analog , _curr_pin , AP_BATT_CURR_PIN ) ,
// @Param: VOLT_MULT
// @DisplayName: Voltage Multiplier
// @Description: Used to convert the voltage of the voltage sensing pin (@PREFIX@VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
// @User: Advanced
AP_GROUPINFO ( " VOLT_MULT " , 3 , AP_BattMonitor_Analog , _volt_multiplier , AP_BATT_VOLTDIVIDER_DEFAULT ) ,
// @Param: AMP_PERVLT
// @DisplayName: Amps per volt
2022-11-22 17:00:11 -04:00
// @Description: Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.
2021-06-24 02:38:19 -03:00
// @Units: A/V
// @User: Standard
AP_GROUPINFO ( " AMP_PERVLT " , 4 , AP_BattMonitor_Analog , _curr_amp_per_volt , AP_BATT_CURR_AMP_PERVOLT_DEFAULT ) ,
// @Param: AMP_OFFSET
// @DisplayName: AMP offset
2022-11-22 17:00:11 -04:00
// @Description: Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.
2021-06-24 02:38:19 -03:00
// @Units: V
// @User: Standard
2021-08-16 21:53:22 -03:00
AP_GROUPINFO ( " AMP_OFFSET " , 5 , AP_BattMonitor_Analog , _curr_amp_offset , AP_BATT_CURR_AMP_OFFSET_DEFAULT ) ,
2021-06-24 02:38:19 -03:00
2021-11-12 02:49:27 -04:00
// @Param: VLT_OFFSET
2022-10-31 10:15:03 -03:00
// @DisplayName: Voltage offset
2022-11-22 17:00:11 -04:00
// @Description: Voltage offset on voltage pin. This allows for an offset due to a diode. This voltage is subtracted before the scaling is applied.
2021-11-12 02:49:27 -04:00
// @Units: V
// @User: Advanced
AP_GROUPINFO ( " VLT_OFFSET " , 6 , AP_BattMonitor_Analog , _volt_offset , 0 ) ,
2021-11-01 13:23:28 -03:00
// Param indexes must be less than 10 to avoid conflict with other battery monitor param tables loaded by pointer
2021-06-24 02:38:19 -03:00
AP_GROUPEND
} ;
2014-12-04 01:35:31 -04:00
/// Constructor
2017-10-27 02:36:49 -03:00
AP_BattMonitor_Analog : : AP_BattMonitor_Analog ( AP_BattMonitor & mon ,
AP_BattMonitor : : BattMonitor_State & mon_state ,
AP_BattMonitor_Params & params ) :
AP_BattMonitor_Backend ( mon , mon_state , params )
2014-12-04 01:35:31 -04:00
{
2021-06-24 02:38:19 -03:00
AP_Param : : setup_object_defaults ( this , var_info ) ;
_state . var_info = var_info ;
_volt_pin_analog_source = hal . analogin - > channel ( _volt_pin ) ;
_curr_pin_analog_source = hal . analogin - > channel ( _curr_pin ) ;
2015-03-18 08:06:25 -03:00
2014-12-04 01:35:31 -04:00
}
// read - read the voltage and current
void
AP_BattMonitor_Analog : : read ( )
{
// this copes with changing the pin at runtime
2021-09-22 16:46:06 -03:00
_state . healthy = _volt_pin_analog_source - > set_pin ( _volt_pin ) ;
2014-12-04 01:35:31 -04:00
// get voltage
2021-11-12 02:49:27 -04:00
_state . voltage = ( _volt_pin_analog_source - > voltage_average ( ) - _volt_offset ) * _volt_multiplier ;
2014-12-04 01:35:31 -04:00
// read current
2017-05-24 04:43:10 -03:00
if ( has_current ( ) ) {
2014-12-04 01:35:31 -04:00
// calculate time since last current read
2022-03-22 21:01:25 -03:00
const uint32_t tnow = AP_HAL : : micros ( ) ;
const uint32_t dt_us = tnow - _state . last_time_micros ;
2014-12-04 01:35:31 -04:00
// this copes with changing the pin at runtime
2021-09-22 16:46:06 -03:00
_state . healthy & = _curr_pin_analog_source - > set_pin ( _curr_pin ) ;
2014-12-04 01:35:31 -04:00
// read current
2021-06-24 02:38:19 -03:00
_state . current_amps = ( _curr_pin_analog_source - > voltage_average ( ) - _curr_amp_offset ) * _curr_amp_per_volt ;
2014-12-04 01:35:31 -04:00
2022-03-22 21:01:25 -03:00
update_consumed ( _state , dt_us ) ;
2014-12-04 01:35:31 -04:00
// record time
_state . last_time_micros = tnow ;
}
}
2017-05-24 04:43:10 -03:00
/// return true if battery provides current info
bool AP_BattMonitor_Analog : : has_current ( ) const
{
2020-08-06 02:33:07 -03:00
return ( ( AP_BattMonitor : : Type ) _params . _type . get ( ) = = AP_BattMonitor : : Type : : ANALOG_VOLTAGE_AND_CURRENT ) ;
2017-05-24 04:43:10 -03:00
}