Blackbox device type 'file' (SITL) considered working when file handler is available
[inav.git] / src / main / sensors / battery_config_structs.h
blob829ac8d87947a6892a20f3395c88a645a932d948
1 /*
2 * This file is part of INAV
4 * INAV free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * INAV distributed in the hope that it
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
21 #pragma once
23 #include <stdbool.h>
24 #include <stdint.h>
26 #include "platform.h"
28 typedef enum {
29 CURRENT_SENSOR_NONE = 0,
30 CURRENT_SENSOR_ADC,
31 CURRENT_SENSOR_VIRTUAL,
32 CURRENT_SENSOR_FAKE,
33 CURRENT_SENSOR_ESC,
34 CURRENT_SENSOR_MAX = CURRENT_SENSOR_FAKE
35 } currentSensor_e;
37 typedef enum {
38 VOLTAGE_SENSOR_NONE = 0,
39 VOLTAGE_SENSOR_ADC,
40 VOLTAGE_SENSOR_ESC,
41 VOLTAGE_SENSOR_FAKE
42 } voltageSensor_e;
44 typedef enum {
45 BAT_CAPACITY_UNIT_MAH,
46 BAT_CAPACITY_UNIT_MWH,
47 } batCapacityUnit_e;
49 typedef enum {
50 BAT_VOLTAGE_RAW,
51 BAT_VOLTAGE_SAG_COMP
52 } batVoltageSource_e;
54 typedef struct batteryMetersConfig_s {
56 #ifdef USE_ADC
57 struct {
58 uint16_t scale;
59 voltageSensor_e type;
60 } voltage;
61 #endif
63 struct {
64 int16_t scale; // scale the current sensor output voltage to milliamps. Value in 1/10th mV/A
65 int16_t offset; // offset of the current sensor in millivolt steps
66 currentSensor_e type; // type of current meter used, either ADC or virtual
67 } current;
69 batVoltageSource_e voltageSource;
71 batCapacityUnit_e capacity_unit; // Describes unit of capacity.value, capacity.warning and capacity.critical
73 uint32_t cruise_power; // power drawn by the motor(s) at cruise throttle/speed (cW)
74 uint16_t idle_power; // power drawn by the system when the motor(s) are stopped (cW)
75 uint8_t rth_energy_margin; // Energy that should be left after RTH (%), used for remaining time/distance before RTH
77 float throttle_compensation_weight;
79 } batteryMetersConfig_t;
81 typedef struct batteryProfile_s {
83 #ifdef USE_ADC
84 uint8_t cells;
86 struct {
87 uint16_t cellDetect; // maximum voltage per cell, used for auto-detecting battery cell count in 0.01V units, default is 430 (4.3V)
88 uint16_t cellMax; // maximum voltage per cell, used for auto-detecting battery voltage in 0.01V units, default is 421 (4.21V)
89 uint16_t cellMin; // minimum voltage per cell, this triggers battery critical alarm, in 0.01V units, default is 330 (3.3V)
90 uint16_t cellWarning; // warning voltage per cell, this triggers battery warning alarm, in 0.01V units, default is 350 (3.5V)
91 } voltage;
92 #endif
94 struct {
95 uint32_t value; // mAh or mWh (see batteryMetersConfig()->capacity_unit)
96 uint32_t warning; // mAh or mWh (see batteryMetersConfig()->capacity_unit)
97 uint32_t critical; // mAh or mWh (see batteryMetersConfig()->capacity_unit)
98 } capacity;
100 uint8_t controlRateProfile;
102 struct {
103 float throttleIdle; // Throttle IDLE value based on min_command, max_throttle, in percent
104 float throttleScale; // Scaling factor for throttle.
105 #ifdef USE_DSHOT
106 uint8_t turtleModePowerFactor; // Power factor from 0 to 100% of flip over after crash
107 #endif
108 } motor;
110 uint16_t failsafe_throttle; // Throttle level used for landing - specify value between 1000..2000 (pwm pulse width for slightly below hover). center throttle = 1500.
112 struct {
114 struct {
115 uint16_t hover_throttle; // multicopter hover throttle
116 } mc;
118 struct {
119 uint16_t cruise_throttle; // Cruise throttle
120 uint16_t min_throttle; // Minimum allowed throttle in auto mode
121 uint16_t max_throttle; // Maximum allowed throttle in auto mode
122 uint8_t pitch_to_throttle; // Pitch angle (in deg) to throttle gain (in 1/1000's of throttle) (*10)
123 uint16_t launch_idle_throttle; // Throttle to keep at launch idle
124 uint16_t launch_throttle; // Launch throttle
125 } fw;
127 } nav;
129 #if defined(USE_POWER_LIMITS)
130 struct {
131 uint16_t continuousCurrent; // dA
132 uint16_t burstCurrent; // dA
133 uint16_t burstCurrentTime; // ds
134 uint16_t burstCurrentFalldownTime; // ds
136 #ifdef USE_ADC
137 uint16_t continuousPower; // dW
138 uint16_t burstPower; // dW
139 uint16_t burstPowerTime; // ds
140 uint16_t burstPowerFalldownTime; // ds
141 #endif // USE_ADC
142 } powerLimits;
143 #endif // USE_POWER_LIMITS
145 } batteryProfile_t;