Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp
Views: 1798
#include "AP_BattMonitor_config.h"12#if AP_BATTERY_ANALOG_ENABLED34#include <AP_HAL/AP_HAL.h>5#include <AP_Common/AP_Common.h>6#include <AP_Math/AP_Math.h>7#include <AP_BoardConfig/AP_BoardConfig.h>89#include "AP_BattMonitor_Analog.h"1011extern const AP_HAL::HAL& hal;1213const AP_Param::GroupInfo AP_BattMonitor_Analog::var_info[] = {1415// @Param: VOLT_PIN16// @DisplayName: Battery Voltage sensing pin17// @Description: Sets the analog input pin that should be used for voltage monitoring.18// @Values: -1:Disabled, 2:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 5:Navigator, 13:Pixhawk2_PM2/CubeOrange_PM2, 14:CubeOrange, 16:Durandal, 100:PX4-v119// @User: Standard20// @RebootRequired: True21AP_GROUPINFO("VOLT_PIN", 1, AP_BattMonitor_Analog, _volt_pin, AP_BATT_VOLT_PIN),2223// @Param: CURR_PIN24// @DisplayName: Battery Current sensing pin25// @Description: Sets the analog input pin that should be used for current monitoring.26// @Values: -1:Disabled, 3:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 4:CubeOrange_PM2/Navigator, 14:Pixhawk2_PM2, 15:CubeOrange, 17:Durandal, 101:PX4-v127// @User: Standard28// @RebootRequired: True29AP_GROUPINFO("CURR_PIN", 2, AP_BattMonitor_Analog, _curr_pin, AP_BATT_CURR_PIN),3031// @Param: VOLT_MULT32// @DisplayName: Voltage Multiplier33// @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.34// @User: Advanced35AP_GROUPINFO("VOLT_MULT", 3, AP_BattMonitor_Analog, _volt_multiplier, AP_BATT_VOLTDIVIDER_DEFAULT),3637// @Param: AMP_PERVLT38// @DisplayName: Amps per volt39// @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.40// @Units: A/V41// @User: Standard42AP_GROUPINFO("AMP_PERVLT", 4, AP_BattMonitor_Analog, _curr_amp_per_volt, AP_BATT_CURR_AMP_PERVOLT_DEFAULT),4344// @Param: AMP_OFFSET45// @DisplayName: AMP offset46// @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.47// @Units: V48// @User: Standard49AP_GROUPINFO("AMP_OFFSET", 5, AP_BattMonitor_Analog, _curr_amp_offset, AP_BATT_CURR_AMP_OFFSET_DEFAULT),5051// @Param: VLT_OFFSET52// @DisplayName: Voltage offset53// @Description: Voltage offset on voltage pin. This allows for an offset due to a diode. This voltage is subtracted before the scaling is applied.54// @Units: V55// @User: Advanced56AP_GROUPINFO("VLT_OFFSET", 6, AP_BattMonitor_Analog, _volt_offset, 0),5758// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS5960AP_GROUPEND61};6263/// Constructor64AP_BattMonitor_Analog::AP_BattMonitor_Analog(AP_BattMonitor &mon,65AP_BattMonitor::BattMonitor_State &mon_state,66AP_BattMonitor_Params ¶ms) :67AP_BattMonitor_Backend(mon, mon_state, params)68{69AP_Param::setup_object_defaults(this, var_info);7071// no other good way of setting these defaults72#if AP_BATT_MONITOR_MAX_INSTANCES > 173if (mon_state.instance == 1) {74#ifdef HAL_BATT2_VOLT_PIN75_volt_pin.set_default(HAL_BATT2_VOLT_PIN);76#endif77#ifdef HAL_BATT2_CURR_PIN78_curr_pin.set_default(HAL_BATT2_CURR_PIN);79#endif80#ifdef HAL_BATT2_VOLT_SCALE81_volt_multiplier.set_default(HAL_BATT2_VOLT_SCALE);82#endif83#ifdef HAL_BATT2_CURR_SCALE84_curr_amp_per_volt.set_default(HAL_BATT2_CURR_SCALE);85#endif86}87#endif88_state.var_info = var_info;8990_volt_pin_analog_source = hal.analogin->channel(_volt_pin);91if (_volt_pin_analog_source == nullptr) {92AP_BoardConfig::config_error("No analog channels for battery %d", mon_state.instance);93}94if ((AP_BattMonitor::Type)_params._type.get() == AP_BattMonitor::Type::ANALOG_VOLTAGE_AND_CURRENT) {95_curr_pin_analog_source = hal.analogin->channel(_curr_pin);96if (_curr_pin_analog_source == nullptr) {97AP_BoardConfig::config_error("No analog channels for battery %d", mon_state.instance);98}99}100101}102103// read - read the voltage and current104void105AP_BattMonitor_Analog::read()106{107// this copes with changing the pin at runtime108_state.healthy = _volt_pin_analog_source->set_pin(_volt_pin);109110// get voltage111_state.voltage = (_volt_pin_analog_source->voltage_average() - _volt_offset) * _volt_multiplier;112113// read current114if (has_current()) {115// calculate time since last current read116const uint32_t tnow = AP_HAL::micros();117const uint32_t dt_us = tnow - _state.last_time_micros;118119// this copes with changing the pin at runtime120_state.healthy &= _curr_pin_analog_source->set_pin(_curr_pin);121122// read current123_state.current_amps = (_curr_pin_analog_source->voltage_average() - _curr_amp_offset) * _curr_amp_per_volt;124125update_consumed(_state, dt_us);126127// record time128_state.last_time_micros = tnow;129}130}131132/// return true if battery provides current info133bool AP_BattMonitor_Analog::has_current() const134{135return (_curr_pin_analog_source != nullptr) &&136((AP_BattMonitor::Type)_params._type.get() == AP_BattMonitor::Type::ANALOG_VOLTAGE_AND_CURRENT);137}138139#endif // AP_BATTERY_ANALOG_ENABLED140141142