2014-12-04 01:35:31 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
#ifndef AP_BATTMONITOR_ANALOG_H
|
|
|
|
#define AP_BATTMONITOR_ANALOG_H
|
|
|
|
|
2015-08-11 03:28:42 -03:00
|
|
|
#include <AP_ADC/AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
|
|
|
|
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
|
2014-12-04 01:35:31 -04:00
|
|
|
#include "AP_BattMonitor.h"
|
|
|
|
#include "AP_BattMonitor_Backend.h"
|
|
|
|
|
|
|
|
// default pins and dividers
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
|
|
|
# define AP_BATT_VOLT_PIN 0 // Battery voltage on A0
|
|
|
|
# define AP_BATT_CURR_PIN 1 // Battery current on A1
|
2015-04-24 00:27:19 -03:00
|
|
|
# define AP_BATT_VOLTDIVIDER_DEFAULT 3.56f // on-board APM1 voltage divider with a 3.9kOhm resistor
|
2014-12-04 01:35:31 -04:00
|
|
|
# define AP_BATT_CURR_AMP_PERVOLT_DEFAULT 0
|
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
|
|
|
# define AP_BATT_VOLT_PIN 13 // APM2.5/2.6 with 3dr power module
|
|
|
|
# define AP_BATT_CURR_PIN 12
|
2015-04-24 00:27:19 -03:00
|
|
|
# define AP_BATT_VOLTDIVIDER_DEFAULT 10.1f
|
|
|
|
# define AP_BATT_CURR_AMP_PERVOLT_DEFAULT 17.0f
|
2014-12-04 01:35:31 -04:00
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE
|
|
|
|
// Flymaple board pin 20 is connected to the external battery supply
|
|
|
|
// via a 24k/5.1k voltage divider. The schematic claims the divider is 25k/5k,
|
|
|
|
// but the actual installed resistors are not so.
|
|
|
|
// So the divider ratio is 5.70588 = (24000+5100)/5100
|
|
|
|
# define AP_BATT_VOLT_PIN 20
|
|
|
|
# define AP_BATT_CURR_PIN 19
|
2015-04-24 00:27:19 -03:00
|
|
|
# define AP_BATT_VOLTDIVIDER_DEFAULT 5.70588f
|
|
|
|
# define AP_BATT_CURR_AMP_PERVOLT_DEFAULT 17.0f
|
2014-12-04 01:35:31 -04:00
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4 && defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
|
|
|
// px4
|
|
|
|
# define AP_BATT_VOLT_PIN 100
|
|
|
|
# define AP_BATT_CURR_PIN 101
|
2015-04-24 00:27:19 -03:00
|
|
|
# define AP_BATT_VOLTDIVIDER_DEFAULT 1.1f
|
|
|
|
# define AP_BATT_CURR_AMP_PERVOLT_DEFAULT 17.0f
|
2014-12-04 01:35:31 -04:00
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4 && defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
|
|
|
// pixhawk
|
|
|
|
# define AP_BATT_VOLT_PIN 2
|
|
|
|
# define AP_BATT_CURR_PIN 3
|
2015-04-24 00:27:19 -03:00
|
|
|
# define AP_BATT_VOLTDIVIDER_DEFAULT 10.1f
|
|
|
|
# define AP_BATT_CURR_AMP_PERVOLT_DEFAULT 17.0f
|
2015-05-04 03:16:12 -03:00
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
2014-12-04 01:35:31 -04:00
|
|
|
# define AP_BATT_VOLT_PIN 13
|
|
|
|
# define AP_BATT_CURR_PIN 12
|
2015-04-24 00:27:19 -03:00
|
|
|
# define AP_BATT_VOLTDIVIDER_DEFAULT 10.1f
|
|
|
|
# define AP_BATT_CURR_AMP_PERVOLT_DEFAULT 17.0f
|
2015-01-05 04:26:09 -04:00
|
|
|
|
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
|
|
|
#if defined(CONFIG_ARCH_BOARD_VRBRAIN_V45) || defined(CONFIG_ARCH_BOARD_VRBRAIN_V51) || defined(CONFIG_ARCH_BOARD_VRBRAIN_V52)
|
2014-12-04 01:35:31 -04:00
|
|
|
# define AP_BATT_VOLT_PIN 10
|
|
|
|
# define AP_BATT_CURR_PIN 11
|
2015-04-24 00:27:19 -03:00
|
|
|
# define AP_BATT_VOLTDIVIDER_DEFAULT 10.1f
|
|
|
|
# define AP_BATT_CURR_AMP_PERVOLT_DEFAULT 17.0f
|
2015-01-05 04:26:09 -04:00
|
|
|
#elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V51)
|
2014-12-04 01:35:31 -04:00
|
|
|
# define AP_BATT_VOLT_PIN 10
|
2015-01-05 04:26:09 -04:00
|
|
|
# define AP_BATT_CURR_PIN -1
|
2015-04-24 00:27:19 -03:00
|
|
|
# define AP_BATT_VOLTDIVIDER_DEFAULT 10.1f
|
|
|
|
# define AP_BATT_CURR_AMP_PERVOLT_DEFAULT 17.0f
|
2015-01-05 04:26:09 -04:00
|
|
|
#elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52)
|
2014-12-04 01:35:31 -04:00
|
|
|
# define AP_BATT_VOLT_PIN 10
|
2015-01-05 04:26:09 -04:00
|
|
|
# define AP_BATT_CURR_PIN 1
|
2015-04-24 00:27:19 -03:00
|
|
|
# define AP_BATT_VOLTDIVIDER_DEFAULT 10.1f
|
|
|
|
# define AP_BATT_CURR_AMP_PERVOLT_DEFAULT 17.0f
|
2015-01-05 04:26:09 -04:00
|
|
|
#endif
|
2014-12-04 01:35:31 -04:00
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN && defined(CONFIG_ARCH_BOARD_VRHERO_V10)
|
|
|
|
# define AP_BATT_VOLT_PIN 100
|
|
|
|
# define AP_BATT_CURR_PIN 101
|
2015-04-24 00:27:19 -03:00
|
|
|
# define AP_BATT_VOLTDIVIDER_DEFAULT 1.1f
|
|
|
|
# define AP_BATT_CURR_AMP_PERVOLT_DEFAULT 17.0f
|
2014-12-04 01:35:31 -04:00
|
|
|
#else
|
|
|
|
# define AP_BATT_VOLT_PIN -1
|
|
|
|
# define AP_BATT_CURR_PIN -1
|
2015-04-24 00:27:19 -03:00
|
|
|
# define AP_BATT_VOLTDIVIDER_DEFAULT 10.1f
|
|
|
|
# define AP_BATT_CURR_AMP_PERVOLT_DEFAULT 17.0f
|
2014-12-04 01:35:31 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
// Other values normally set directly by mission planner
|
|
|
|
// # define AP_BATT_VOLTDIVIDER_DEFAULT 15.70 // Volt divider for AttoPilot 50V/90A sensor
|
|
|
|
// # define AP_BATT_VOLTDIVIDER_DEFAULT 4.127 // Volt divider for AttoPilot 13.6V/45A sensor
|
|
|
|
// # define AP_BATT_CURR_AMP_PERVOLT_DEFAULT 27.32 // Amp/Volt for AttoPilot 50V/90A sensor
|
|
|
|
// # define AP_BATT_CURR_AMP_PERVOLT_DEFAULT 13.66 // Amp/Volt for AttoPilot 13.6V/45A sensor
|
|
|
|
|
|
|
|
class AP_BattMonitor_Analog : public AP_BattMonitor_Backend
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
|
|
|
|
/// Constructor
|
|
|
|
AP_BattMonitor_Analog(AP_BattMonitor &mon, uint8_t instance, AP_BattMonitor::BattMonitor_State &mon_state);
|
|
|
|
|
|
|
|
/// Read the battery voltage and current. Should be called at 10hz
|
|
|
|
void read();
|
|
|
|
|
|
|
|
protected:
|
|
|
|
|
|
|
|
AP_HAL::AnalogSource *_volt_pin_analog_source;
|
|
|
|
AP_HAL::AnalogSource *_curr_pin_analog_source;
|
|
|
|
};
|
|
|
|
#endif // AP_BATTMONITOR_ANALOG_H
|