2013-09-28 10:35:27 -03:00
# include "AP_BattMonitor.h"
2014-12-04 01:27:56 -04:00
# include "AP_BattMonitor_Analog.h"
# include "AP_BattMonitor_SMBus.h"
2015-07-23 06:16:37 -03:00
# include "AP_BattMonitor_Bebop.h"
2016-07-25 22:10:17 -03:00
# include <AP_Vehicle/AP_Vehicle_Type.h>
2013-09-28 10:35:27 -03:00
extern const AP_HAL : : HAL & hal ;
2015-10-25 14:03:46 -03:00
const AP_Param : : GroupInfo AP_BattMonitor : : var_info [ ] = {
2015-08-25 23:13:57 -03:00
// @Param: _MONITOR
2013-09-28 10:35:27 -03:00
// @DisplayName: Battery monitoring
// @Description: Controls enabling monitoring of the battery's voltage and current
2017-02-15 06:01:59 -04:00
// @Values: 0:Disabled,3:Analog Voltage Only,4:Analog Voltage and Current,5:Solo,6:Bebop,7:SMBus-Maxell
2013-09-28 10:35:27 -03:00
// @User: Standard
2014-12-04 03:05:28 -04:00
AP_GROUPINFO ( " _MONITOR " , 0 , AP_BattMonitor , _monitoring [ 0 ] , BattMonitor_TYPE_NONE ) ,
2013-09-28 10:35:27 -03:00
2015-08-25 23:13:57 -03:00
// @Param: _VOLT_PIN
2013-09-28 10:35:27 -03:00
// @DisplayName: Battery Voltage sensing pin
2017-04-13 00:49:25 -03:00
// @Description: Setting this to 0 ~ 13 will enable battery voltage sensing on pins A0 ~ A13. For APM2.x power brick it should be set to 13. On the PX4-v1 it should be set to 100. On the Pixhawk, Pixracer and NAVIO board's PM connector it should be set to 2, Pixhawk2 Power2 is 13.
// @Values: -1:Disabled, 0:A0, 1:A1, 2:Pixhawk/Pixracer/Navio2, 5:A5, 10:A10, 13:A13/Pixhawk2_PM2, 100:PX4-v1
2013-09-28 10:35:27 -03:00
// @User: Standard
2014-12-04 01:27:56 -04:00
AP_GROUPINFO ( " _VOLT_PIN " , 1 , AP_BattMonitor , _volt_pin [ 0 ] , AP_BATT_VOLT_PIN ) ,
2013-09-28 10:35:27 -03:00
2015-08-25 23:13:57 -03:00
// @Param: _CURR_PIN
2013-09-28 10:35:27 -03:00
// @DisplayName: Battery Current sensing pin
2017-04-13 00:49:25 -03:00
// @Description: Setting this to 0 ~ 13 will enable battery current sensing on pins A0 ~ A13. For the 3DR power brick on APM2.5 it should be set to 12. On the PX4 it should be set to 101. On the Pixhawk powered from the PM connector it should be set to 3, Pixhawk2 Power2 is 12.
// @Values: -1:Disabled, 1:A1, 2:A2, 3:Pixhawk/Pixracer/Navio2, 11:A11, 12:A12/Pixhawk2_PM2, 101:PX4-v1
2013-09-28 10:35:27 -03:00
// @User: Standard
2014-12-04 01:27:56 -04:00
AP_GROUPINFO ( " _CURR_PIN " , 2 , AP_BattMonitor , _curr_pin [ 0 ] , AP_BATT_CURR_PIN ) ,
2013-09-28 10:35:27 -03:00
2015-08-25 23:13:57 -03:00
// @Param: _VOLT_MULT
2013-09-30 02:17:08 -03:00
// @DisplayName: Voltage Multiplier
2013-10-09 19:33:03 -03:00
// @Description: Used to convert the voltage of the voltage sensing pin (BATT_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick on APM2 or Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX4 using the PX4IO power supply this should be set to 1.
2013-09-28 10:35:27 -03:00
// @User: Advanced
2014-12-04 01:27:56 -04:00
AP_GROUPINFO ( " _VOLT_MULT " , 3 , AP_BattMonitor , _volt_multiplier [ 0 ] , AP_BATT_VOLTDIVIDER_DEFAULT ) ,
2013-09-28 10:35:27 -03:00
2015-08-25 23:13:57 -03:00
// @Param: _AMP_PERVOLT
2013-10-09 19:33:03 -03:00
// @DisplayName: Amps per volt
// @Description: Number of amps that a 1V reading on the current sensor corresponds to. On the APM2 or Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
2014-10-14 00:42:45 -03:00
// @Units: Amps/Volt
2013-09-28 10:35:27 -03:00
// @User: Standard
2014-12-04 01:27:56 -04:00
AP_GROUPINFO ( " _AMP_PERVOLT " , 4 , AP_BattMonitor , _curr_amp_per_volt [ 0 ] , AP_BATT_CURR_AMP_PERVOLT_DEFAULT ) ,
2013-09-28 10:35:27 -03:00
2015-08-25 23:13:57 -03:00
// @Param: _AMP_OFFSET
2013-09-28 10:35:27 -03:00
// @DisplayName: AMP offset
// @Description: Voltage offset at zero current on current sensor
// @Units: Volts
// @User: Standard
2014-12-04 01:27:56 -04:00
AP_GROUPINFO ( " _AMP_OFFSET " , 5 , AP_BattMonitor , _curr_amp_offset [ 0 ] , 0 ) ,
2013-09-28 10:35:27 -03:00
2015-08-25 23:13:57 -03:00
// @Param: _CAPACITY
2013-09-28 10:35:27 -03:00
// @DisplayName: Battery capacity
// @Description: Capacity of the battery in mAh when full
// @Units: mAh
2013-10-28 23:23:27 -03:00
// @Increment: 50
2013-09-28 10:35:27 -03:00
// @User: Standard
2014-12-04 01:27:56 -04:00
AP_GROUPINFO ( " _CAPACITY " , 6 , AP_BattMonitor , _pack_capacity [ 0 ] , AP_BATT_CAPACITY_DEFAULT ) ,
2013-09-28 10:35:27 -03:00
2014-12-04 01:27:56 -04:00
// 7 & 8 were used for VOLT2_PIN and VOLT2_MULT
2016-01-08 13:16:29 -04:00
2016-04-19 21:21:48 -03:00
# if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
2016-01-08 13:16:29 -04:00
// @Param: _WATT_MAX
// @DisplayName: Maximum allowed power (Watts)
// @Description: If battery wattage (voltage * current) exceeds this value then the system will reduce max throttle (THR_MAX, TKOFF_THR_MAX and THR_MIN for reverse thrust) to satisfy this limit. This helps limit high current to low C rated batteries regardless of battery voltage. The max throttle will slowly grow back to THR_MAX (or TKOFF_THR_MAX ) and THR_MIN if demanding the current max and under the watt max. Use 0 to disable.
// @Units: Watts
// @Increment: 1
// @User: Advanced
AP_GROUPINFO ( " _WATT_MAX " , 9 , AP_BattMonitor , _watt_max [ 0 ] , AP_BATT_MAX_WATT_DEFAULT ) ,
2016-04-19 21:21:48 -03:00
# endif
2016-01-08 13:16:29 -04:00
// 10 is left for future expansion
2014-12-04 01:27:56 -04:00
# if AP_BATT_MONITOR_MAX_INSTANCES > 1
// @Param: 2_MONITOR
// @DisplayName: Battery monitoring
// @Description: Controls enabling monitoring of the battery's voltage and current
2017-02-15 06:01:59 -04:00
// @Values: 0:Disabled,3:Analog Voltage Only,4:Analog Voltage and Current,5:Solo,6:Bebop,7:SMBus-Maxell
2014-12-04 01:27:56 -04:00
// @User: Standard
2014-12-04 03:05:28 -04:00
AP_GROUPINFO ( " 2_MONITOR " , 11 , AP_BattMonitor , _monitoring [ 1 ] , BattMonitor_TYPE_NONE ) ,
2014-12-04 01:27:56 -04:00
// @Param: 2_VOLT_PIN
// @DisplayName: Battery Voltage sensing pin
2017-04-13 00:49:25 -03:00
// @Description: Setting this to 0 ~ 13 will enable battery voltage sensing on pins A0 ~ A13. For APM2.x power brick it should be set to 13. On the PX4-v1 it should be set to 100. On the Pixhawk, Pixracer and NAVIO board's PM connector it should be set to 2, Pixhawk2 Power2 is 13.
// @Values: -1:Disabled, 0:A0, 1:A1, 2:Pixhawk/Pixracer/Navio2, 5:A5, 10:A10, 13:A13/Pixhawk2_PM2, 100:PX4-v1
2014-08-08 23:13:49 -03:00
// @User: Standard
2014-12-04 01:27:56 -04:00
AP_GROUPINFO ( " 2_VOLT_PIN " , 12 , AP_BattMonitor , _volt_pin [ 1 ] , AP_BATT_VOLT_PIN ) ,
2014-08-08 23:13:49 -03:00
2014-12-04 01:27:56 -04:00
// @Param: 2_CURR_PIN
// @DisplayName: Battery Current sensing pin
2017-04-13 00:49:25 -03:00
// @Description: Setting this to 0 ~ 13 will enable battery current sensing on pins A0 ~ A13. For the 3DR power brick on APM2.5 it should be set to 12. On the PX4 it should be set to 101. On the Pixhawk powered from the PM connector it should be set to 3, Pixhawk2 Power2 is 12.
// @Values: -1:Disabled, 1:A1, 2:A2, 3:Pixhawk/Pixracer/Navio2, 11:A11, 12:A12/Pixhawk2_PM2, 101:PX4-v1
2014-12-04 01:27:56 -04:00
// @User: Standard
AP_GROUPINFO ( " 2_CURR_PIN " , 13 , AP_BattMonitor , _curr_pin [ 1 ] , AP_BATT_CURR_PIN ) ,
// @Param: 2_VOLT_MULT
// @DisplayName: Voltage Multiplier
// @Description: Used to convert the voltage of the voltage sensing pin (BATT_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick on APM2 or Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX4 using the PX4IO power supply this should be set to 1.
2014-08-08 23:13:49 -03:00
// @User: Advanced
2014-12-04 01:27:56 -04:00
AP_GROUPINFO ( " 2_VOLT_MULT " , 14 , AP_BattMonitor , _volt_multiplier [ 1 ] , AP_BATT_VOLTDIVIDER_DEFAULT ) ,
// @Param: 2_AMP_PERVOL
// @DisplayName: Amps per volt
// @Description: Number of amps that a 1V reading on the current sensor corresponds to. On the APM2 or Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
// @Units: Amps/Volt
// @User: Standard
AP_GROUPINFO ( " 2_AMP_PERVOL " , 15 , AP_BattMonitor , _curr_amp_per_volt [ 1 ] , AP_BATT_CURR_AMP_PERVOLT_DEFAULT ) ,
// @Param: 2_AMP_OFFSET
// @DisplayName: AMP offset
// @Description: Voltage offset at zero current on current sensor
// @Units: Volts
// @User: Standard
AP_GROUPINFO ( " 2_AMP_OFFSET " , 16 , AP_BattMonitor , _curr_amp_offset [ 1 ] , 0 ) ,
// @Param: 2_CAPACITY
// @DisplayName: Battery capacity
// @Description: Capacity of the battery in mAh when full
// @Units: mAh
// @Increment: 50
// @User: Standard
AP_GROUPINFO ( " 2_CAPACITY " , 17 , AP_BattMonitor , _pack_capacity [ 1 ] , AP_BATT_CAPACITY_DEFAULT ) ,
2016-01-08 13:16:29 -04:00
2016-04-19 21:21:48 -03:00
# if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
2016-01-08 13:16:29 -04:00
// @Param: 2_WATT_MAX
// @DisplayName: Maximum allowed current
// @Description: If battery wattage (voltage * current) exceeds this value then the system will reduce max throttle (THR_MAX, TKOFF_THR_MAX and THR_MIN for reverse thrust) to satisfy this limit. This helps limit high current to low C rated batteries regardless of battery voltage. The max throttle will slowly grow back to THR_MAX (or TKOFF_THR_MAX ) and THR_MIN if demanding the current max and under the watt max. Use 0 to disable.
// @Units: Amps
// @Increment: 1
// @User: Advanced
AP_GROUPINFO ( " 2_WATT_MAX " , 18 , AP_BattMonitor , _watt_max [ 1 ] , AP_BATT_MAX_WATT_DEFAULT ) ,
2016-04-19 21:21:48 -03:00
# endif
2016-01-08 13:16:29 -04:00
2014-12-04 01:27:56 -04:00
# endif // AP_BATT_MONITOR_MAX_INSTANCES > 1
2014-08-08 23:13:49 -03:00
2013-09-28 10:35:27 -03:00
AP_GROUPEND
} ;
// Default constructor.
// Note that the Vector/Matrix constructors already implicitly zero
// their values.
//
AP_BattMonitor : : AP_BattMonitor ( void ) :
2014-12-04 01:27:56 -04:00
_num_instances ( 0 )
2013-09-28 10:35:27 -03:00
{
AP_Param : : setup_object_defaults ( this , var_info ) ;
}
2014-12-04 01:27:56 -04:00
// init - instantiate the battery monitors
2013-09-28 10:35:27 -03:00
void
AP_BattMonitor : : init ( )
{
2014-12-04 01:27:56 -04:00
// check init has not been called before
if ( _num_instances ! = 0 ) {
return ;
}
2016-06-06 19:14:35 -03:00
# if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
2015-07-23 07:49:48 -03:00
// force monitor for bebop
_monitoring [ 0 ] = BattMonitor_TYPE_BEBOP ;
# endif
2014-12-04 01:27:56 -04:00
// create each instance
for ( uint8_t instance = 0 ; instance < AP_BATT_MONITOR_MAX_INSTANCES ; instance + + ) {
2017-04-08 00:27:31 -03:00
// clear out the cell voltages
memset ( & state [ instance ] . cell_voltages , 0xFF , sizeof ( cells ) ) ;
2014-12-04 01:27:56 -04:00
uint8_t monitor_type = _monitoring [ instance ] ;
2015-07-23 07:49:48 -03:00
switch ( monitor_type ) {
case BattMonitor_TYPE_ANALOG_VOLTAGE_ONLY :
case BattMonitor_TYPE_ANALOG_VOLTAGE_AND_CURRENT :
state [ instance ] . instance = instance ;
drivers [ instance ] = new AP_BattMonitor_Analog ( * this , instance , state [ instance ] ) ;
_num_instances + + ;
break ;
2017-02-08 20:28:14 -04:00
case BattMonitor_TYPE_SOLO :
2015-07-23 07:49:48 -03:00
state [ instance ] . instance = instance ;
2017-02-08 20:28:14 -04:00
drivers [ instance ] = new AP_BattMonitor_SMBus_Solo ( * this , instance , state [ instance ] ,
hal . i2c_mgr - > get_device ( AP_BATTMONITOR_SMBUS_BUS_INTERNAL , AP_BATTMONITOR_SMBUS_I2C_ADDR ) ) ;
_num_instances + + ;
break ;
2017-02-08 20:28:57 -04:00
case BattMonitor_TYPE_MAXELL :
state [ instance ] . instance = instance ;
drivers [ instance ] = new AP_BattMonitor_SMBus_Maxell ( * this , instance , state [ instance ] ,
hal . i2c_mgr - > get_device ( AP_BATTMONITOR_SMBUS_BUS_EXTERNAL , AP_BATTMONITOR_SMBUS_I2C_ADDR ) ) ;
2015-07-23 07:49:48 -03:00
_num_instances + + ;
break ;
case BattMonitor_TYPE_BEBOP :
2016-06-06 19:14:35 -03:00
# if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
2015-07-23 07:49:48 -03:00
state [ instance ] . instance = instance ;
drivers [ instance ] = new AP_BattMonitor_Bebop ( * this , instance , state [ instance ] ) ;
_num_instances + + ;
2014-12-04 01:27:56 -04:00
# endif
2015-07-23 07:49:48 -03:00
break ;
2014-12-04 01:27:56 -04:00
}
2015-04-09 02:37:15 -03:00
// call init function for each backend
2016-10-30 02:24:21 -03:00
if ( drivers [ instance ] ! = nullptr ) {
2015-04-09 02:37:15 -03:00
drivers [ instance ] - > init ( ) ;
}
2014-08-08 23:13:49 -03:00
}
2013-09-28 10:35:27 -03:00
}
2014-12-04 01:27:56 -04:00
// read - read the voltage and current for all instances
2013-09-28 10:35:27 -03:00
void
AP_BattMonitor : : read ( )
{
2016-06-02 19:02:20 -03:00
for ( uint8_t i = 0 ; i < _num_instances ; i + + ) {
2016-10-30 02:24:21 -03:00
if ( drivers [ i ] ! = nullptr & & _monitoring [ i ] ! = BattMonitor_TYPE_NONE ) {
2014-12-04 01:27:56 -04:00
drivers [ i ] - > read ( ) ;
2014-08-08 23:13:49 -03:00
}
2013-09-28 10:35:27 -03:00
}
2014-12-04 01:27:56 -04:00
}
// healthy - returns true if monitor is functioning
bool AP_BattMonitor : : healthy ( uint8_t instance ) const {
2016-06-02 19:02:20 -03:00
return instance < _num_instances & & _BattMonitor_STATE ( instance ) . healthy ;
2014-12-04 01:27:56 -04:00
}
2013-09-28 10:35:27 -03:00
2016-01-06 21:11:12 -04:00
bool AP_BattMonitor : : is_powering_off ( uint8_t instance ) const {
2016-06-02 19:02:20 -03:00
return instance < _num_instances & & _BattMonitor_STATE ( instance ) . is_powering_off ;
2016-01-06 21:11:12 -04:00
}
2014-12-04 01:27:56 -04:00
/// has_current - returns true if battery monitor instance provides current info
bool AP_BattMonitor : : has_current ( uint8_t instance ) const
{
// check for analog voltage and current monitor or smbus monitor
2016-10-30 02:24:21 -03:00
if ( instance < _num_instances & & drivers [ instance ] ! = nullptr ) {
2016-06-02 19:02:20 -03:00
return ( _monitoring [ instance ] = = BattMonitor_TYPE_ANALOG_VOLTAGE_AND_CURRENT | |
2017-02-08 20:28:14 -04:00
_monitoring [ instance ] = = BattMonitor_TYPE_SOLO | |
2017-02-08 20:28:57 -04:00
_monitoring [ instance ] = = BattMonitor_TYPE_BEBOP | |
_monitoring [ instance ] = = BattMonitor_TYPE_MAXELL ) ;
2014-12-04 01:27:56 -04:00
}
// not monitoring current
return false ;
}
/// voltage - returns battery voltage in volts
float AP_BattMonitor : : voltage ( uint8_t instance ) const
{
2016-06-02 19:02:20 -03:00
if ( instance < _num_instances ) {
2014-12-04 01:27:56 -04:00
return _BattMonitor_STATE ( instance ) . voltage ;
} else {
return 0.0f ;
}
}
/// current_amps - returns the instantaneous current draw in amperes
float AP_BattMonitor : : current_amps ( uint8_t instance ) const {
2016-06-02 19:02:20 -03:00
if ( instance < _num_instances ) {
2014-12-04 01:27:56 -04:00
return _BattMonitor_STATE ( instance ) . current_amps ;
} else {
return 0.0f ;
}
}
/// current_total_mah - returns total current drawn since start-up in amp-hours
float AP_BattMonitor : : current_total_mah ( uint8_t instance ) const {
2016-06-02 19:02:20 -03:00
if ( instance < _num_instances ) {
2014-12-04 01:27:56 -04:00
return _BattMonitor_STATE ( instance ) . current_total_mah ;
} else {
return 0.0f ;
2013-09-28 10:35:27 -03:00
}
}
/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
2014-12-04 01:27:56 -04:00
uint8_t AP_BattMonitor : : capacity_remaining_pct ( uint8_t instance ) const
2013-09-28 10:35:27 -03:00
{
2016-10-30 02:24:21 -03:00
if ( instance < _num_instances & & drivers [ instance ] ! = nullptr ) {
2014-12-04 01:27:56 -04:00
return drivers [ instance ] - > capacity_remaining_pct ( ) ;
2016-06-02 19:02:20 -03:00
} else {
return 0 ;
2014-12-04 01:27:56 -04:00
}
2013-09-30 11:14:09 -03:00
}
2016-05-03 11:40:00 -03:00
/// pack_capacity_mah - returns the capacity of the battery pack in mAh when the pack is full
int32_t AP_BattMonitor : : pack_capacity_mah ( uint8_t instance ) const
{
if ( instance < AP_BATT_MONITOR_MAX_INSTANCES ) {
return _pack_capacity [ instance ] ;
} else {
return 0 ;
}
}
2017-02-08 20:28:57 -04:00
2016-05-03 11:40:00 -03:00
/// exhausted - returns true if the voltage remains below the low_voltage for 10 seconds or remaining capacity falls below min_capacity_mah
2014-12-04 01:27:56 -04:00
bool AP_BattMonitor : : exhausted ( uint8_t instance , float low_voltage , float min_capacity_mah )
2013-09-30 11:14:09 -03:00
{
2014-12-04 01:27:56 -04:00
// exit immediately if no monitors setup
2016-06-02 19:02:20 -03:00
if ( _num_instances = = 0 | | instance > = _num_instances ) {
2013-09-30 11:14:09 -03:00
return false ;
}
// check voltage
2016-06-02 19:02:20 -03:00
if ( ( state [ instance ] . voltage > 0 ) & & ( low_voltage > 0 ) & & ( state [ instance ] . voltage < low_voltage ) ) {
2013-09-30 11:14:09 -03:00
// this is the first time our voltage has dropped below minimum so start timer
2014-12-04 01:27:56 -04:00
if ( state [ instance ] . low_voltage_start_ms = = 0 ) {
2016-06-02 19:02:20 -03:00
state [ instance ] . low_voltage_start_ms = AP_HAL : : millis ( ) ;
} else if ( AP_HAL : : millis ( ) - state [ instance ] . low_voltage_start_ms > AP_BATT_LOW_VOLT_TIMEOUT_MS ) {
2013-09-30 11:14:09 -03:00
return true ;
}
2016-06-02 19:02:20 -03:00
} else {
2013-09-30 11:14:09 -03:00
// acceptable voltage so reset timer
2014-12-04 01:27:56 -04:00
state [ instance ] . low_voltage_start_ms = 0 ;
2013-09-30 11:14:09 -03:00
}
// check capacity if current monitoring is enabled
2016-06-02 19:02:20 -03:00
if ( has_current ( instance ) & & ( min_capacity_mah > 0 ) & & ( _pack_capacity [ instance ] - state [ instance ] . current_total_mah < min_capacity_mah ) ) {
2013-09-30 11:14:09 -03:00
return true ;
}
2016-06-02 19:02:20 -03:00
// if we've gotten this far then battery is ok
2013-09-30 11:14:09 -03:00
return false ;
2013-09-28 10:35:27 -03:00
}
2016-01-08 13:16:29 -04:00
// return true if any battery is pushing too much power
bool AP_BattMonitor : : overpower_detected ( ) const
{
bool result = false ;
2016-06-02 19:02:20 -03:00
for ( int instance = 0 ; instance < _num_instances ; instance + + ) {
2016-01-08 13:16:29 -04:00
result | = overpower_detected ( instance ) ;
}
return result ;
}
bool AP_BattMonitor : : overpower_detected ( uint8_t instance ) const
{
2016-07-25 22:10:17 -03:00
# if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
2016-06-02 19:02:20 -03:00
if ( instance < _num_instances & & _watt_max [ instance ] > 0 ) {
2016-01-08 13:16:29 -04:00
float power = _BattMonitor_STATE ( instance ) . current_amps * _BattMonitor_STATE ( instance ) . voltage ;
return _BattMonitor_STATE ( instance ) . healthy & & ( power > _watt_max [ instance ] ) ;
}
return false ;
2016-07-25 22:10:17 -03:00
# else
return false ;
2016-04-19 21:21:48 -03:00
# endif
2016-07-25 22:10:17 -03:00
}
2017-04-08 00:27:31 -03:00
// return the current cell voltages, returns the first monitor instances cells if the instance is out of range
const AP_BattMonitor : : cells & AP_BattMonitor : : get_cell_voltages ( const uint8_t instance ) const
{
if ( instance > = AP_BATT_MONITOR_MAX_INSTANCES ) {
return state [ AP_BATT_PRIMARY_INSTANCE ] . cell_voltages ;
} else {
return state [ instance ] . cell_voltages ;
}
}
2017-04-08 05:20:08 -03:00
// returns true if there is a temperature reading
bool AP_BattMonitor : : get_temperature ( float & temperature , const uint8_t instance ) const
{
if ( instance > = AP_BATT_MONITOR_MAX_INSTANCES ) {
return false ;
} else {
temperature = state [ instance ] . temperature ;
return ( AP_HAL : : millis ( ) - state [ instance ] . temperature_time ) < = AP_BATT_MONITOR_TIMEOUT ;
}
}