CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp
Views: 1798
1
#include "AP_BattMonitor_config.h"
2
3
#if AP_BATTERY_ANALOG_ENABLED
4
5
#include <AP_HAL/AP_HAL.h>
6
#include <AP_Common/AP_Common.h>
7
#include <AP_Math/AP_Math.h>
8
#include <AP_BoardConfig/AP_BoardConfig.h>
9
10
#include "AP_BattMonitor_Analog.h"
11
12
extern const AP_HAL::HAL& hal;
13
14
const AP_Param::GroupInfo AP_BattMonitor_Analog::var_info[] = {
15
16
// @Param: VOLT_PIN
17
// @DisplayName: Battery Voltage sensing pin
18
// @Description: Sets the analog input pin that should be used for voltage monitoring.
19
// @Values: -1:Disabled, 2:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 5:Navigator, 13:Pixhawk2_PM2/CubeOrange_PM2, 14:CubeOrange, 16:Durandal, 100:PX4-v1
20
// @User: Standard
21
// @RebootRequired: True
22
AP_GROUPINFO("VOLT_PIN", 1, AP_BattMonitor_Analog, _volt_pin, AP_BATT_VOLT_PIN),
23
24
// @Param: CURR_PIN
25
// @DisplayName: Battery Current sensing pin
26
// @Description: Sets the analog input pin that should be used for current monitoring.
27
// @Values: -1:Disabled, 3:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 4:CubeOrange_PM2/Navigator, 14:Pixhawk2_PM2, 15:CubeOrange, 17:Durandal, 101:PX4-v1
28
// @User: Standard
29
// @RebootRequired: True
30
AP_GROUPINFO("CURR_PIN", 2, AP_BattMonitor_Analog, _curr_pin, AP_BATT_CURR_PIN),
31
32
// @Param: VOLT_MULT
33
// @DisplayName: Voltage Multiplier
34
// @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.
35
// @User: Advanced
36
AP_GROUPINFO("VOLT_MULT", 3, AP_BattMonitor_Analog, _volt_multiplier, AP_BATT_VOLTDIVIDER_DEFAULT),
37
38
// @Param: AMP_PERVLT
39
// @DisplayName: Amps per volt
40
// @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.
41
// @Units: A/V
42
// @User: Standard
43
AP_GROUPINFO("AMP_PERVLT", 4, AP_BattMonitor_Analog, _curr_amp_per_volt, AP_BATT_CURR_AMP_PERVOLT_DEFAULT),
44
45
// @Param: AMP_OFFSET
46
// @DisplayName: AMP offset
47
// @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.
48
// @Units: V
49
// @User: Standard
50
AP_GROUPINFO("AMP_OFFSET", 5, AP_BattMonitor_Analog, _curr_amp_offset, AP_BATT_CURR_AMP_OFFSET_DEFAULT),
51
52
// @Param: VLT_OFFSET
53
// @DisplayName: Voltage offset
54
// @Description: Voltage offset on voltage pin. This allows for an offset due to a diode. This voltage is subtracted before the scaling is applied.
55
// @Units: V
56
// @User: Advanced
57
AP_GROUPINFO("VLT_OFFSET", 6, AP_BattMonitor_Analog, _volt_offset, 0),
58
59
// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS
60
61
AP_GROUPEND
62
};
63
64
/// Constructor
65
AP_BattMonitor_Analog::AP_BattMonitor_Analog(AP_BattMonitor &mon,
66
AP_BattMonitor::BattMonitor_State &mon_state,
67
AP_BattMonitor_Params &params) :
68
AP_BattMonitor_Backend(mon, mon_state, params)
69
{
70
AP_Param::setup_object_defaults(this, var_info);
71
72
// no other good way of setting these defaults
73
#if AP_BATT_MONITOR_MAX_INSTANCES > 1
74
if (mon_state.instance == 1) {
75
#ifdef HAL_BATT2_VOLT_PIN
76
_volt_pin.set_default(HAL_BATT2_VOLT_PIN);
77
#endif
78
#ifdef HAL_BATT2_CURR_PIN
79
_curr_pin.set_default(HAL_BATT2_CURR_PIN);
80
#endif
81
#ifdef HAL_BATT2_VOLT_SCALE
82
_volt_multiplier.set_default(HAL_BATT2_VOLT_SCALE);
83
#endif
84
#ifdef HAL_BATT2_CURR_SCALE
85
_curr_amp_per_volt.set_default(HAL_BATT2_CURR_SCALE);
86
#endif
87
}
88
#endif
89
_state.var_info = var_info;
90
91
_volt_pin_analog_source = hal.analogin->channel(_volt_pin);
92
if (_volt_pin_analog_source == nullptr) {
93
AP_BoardConfig::config_error("No analog channels for battery %d", mon_state.instance);
94
}
95
if ((AP_BattMonitor::Type)_params._type.get() == AP_BattMonitor::Type::ANALOG_VOLTAGE_AND_CURRENT) {
96
_curr_pin_analog_source = hal.analogin->channel(_curr_pin);
97
if (_curr_pin_analog_source == nullptr) {
98
AP_BoardConfig::config_error("No analog channels for battery %d", mon_state.instance);
99
}
100
}
101
102
}
103
104
// read - read the voltage and current
105
void
106
AP_BattMonitor_Analog::read()
107
{
108
// this copes with changing the pin at runtime
109
_state.healthy = _volt_pin_analog_source->set_pin(_volt_pin);
110
111
// get voltage
112
_state.voltage = (_volt_pin_analog_source->voltage_average() - _volt_offset) * _volt_multiplier;
113
114
// read current
115
if (has_current()) {
116
// calculate time since last current read
117
const uint32_t tnow = AP_HAL::micros();
118
const uint32_t dt_us = tnow - _state.last_time_micros;
119
120
// this copes with changing the pin at runtime
121
_state.healthy &= _curr_pin_analog_source->set_pin(_curr_pin);
122
123
// read current
124
_state.current_amps = (_curr_pin_analog_source->voltage_average() - _curr_amp_offset) * _curr_amp_per_volt;
125
126
update_consumed(_state, dt_us);
127
128
// record time
129
_state.last_time_micros = tnow;
130
}
131
}
132
133
/// return true if battery provides current info
134
bool AP_BattMonitor_Analog::has_current() const
135
{
136
return (_curr_pin_analog_source != nullptr) &&
137
((AP_BattMonitor::Type)_params._type.get() == AP_BattMonitor::Type::ANALOG_VOLTAGE_AND_CURRENT);
138
}
139
140
#endif // AP_BATTERY_ANALOG_ENABLED
141
142