BAT: Consolidate the highest feasible number of batteries into just 3

This commit is contained in:
Claudio Chies 2025-09-17 08:48:36 +02:00 committed by Silvan Fuhrer
parent f90d6c03fc
commit d3acee315a
6 changed files with 7 additions and 13 deletions

View File

@ -394,7 +394,7 @@
*(.text._ZN4EKF215PublishBaroBiasERKy)
*(.text._ZN4EKF221UpdateGyroCalibrationERKy)
*(.text._ZN6matrix9constrainIfLj3ELj1EEENS_6MatrixIT_XT0_EXT1_EEERKS3_S2_S2_)
*(.text._ZN4uORB22SubscriptionMultiArrayI16battery_status_sLh4EE16advertised_countEv)
*(.text._ZN4uORB22SubscriptionMultiArrayI16battery_status_sLh3EE16advertised_countEv)
*(.text._ZN23MavlinkStreamScaledIMU34sendEv)
*(.text.__aeabi_ldivmod)
*(.text._ZN15PositionControl16setInputSetpointERK21trajectory_setpoint_s)

View File

@ -402,7 +402,7 @@
*(.text._ZN4EKF215PublishBaroBiasERKy)
*(.text._ZN4EKF221UpdateGyroCalibrationERKy)
*(.text._ZN6matrix9constrainIfLj3ELj1EEENS_6MatrixIT_XT0_EXT1_EEERKS3_S2_S2_)
*(.text._ZN4uORB22SubscriptionMultiArrayI16battery_status_sLh4EE16advertised_countEv)
*(.text._ZN4uORB22SubscriptionMultiArrayI16battery_status_sLh3EE16advertised_countEv)
*(.text._ZN23MavlinkStreamScaledIMU34sendEv)
*(.text.__aeabi_ldivmod)
*(.text._ZN15PositionControl16setInputSetpointERK21trajectory_setpoint_s)

View File

@ -5,7 +5,7 @@
# Battery instance information is also logged and streamed in MAVLink telemetry.
uint32 MESSAGE_VERSION = 1
uint8 MAX_INSTANCES = 4
uint8 MAX_INSTANCES = 3
uint64 timestamp # [us] Time since system start

View File

@ -173,10 +173,6 @@
# define BOARD_BATT_V_LIST {ADC_BATTERY1_VOLTAGE_CHANNEL, ADC_BATTERY2_VOLTAGE_CHANNEL, ADC_BATTERY3_VOLTAGE_CHANNEL}
# define BOARD_BATT_I_LIST {ADC_BATTERY1_CURRENT_CHANNEL, ADC_BATTERY2_CURRENT_CHANNEL, ADC_BATTERY3_CURRENT_CHANNEL}
# define BOARD_BRICK_VALID_LIST {BOARD_ADC_BRICK1_VALID, BOARD_ADC_BRICK2_VALID, BOARD_ADC_BRICK3_VALID}
#elif BOARD_NUMBER_BRICKS == 4
# define BOARD_BATT_V_LIST {ADC_BATTERY1_VOLTAGE_CHANNEL, ADC_BATTERY2_VOLTAGE_CHANNEL, ADC_BATTERY3_VOLTAGE_CHANNEL, ADC_BATTERY4_VOLTAGE_CHANNEL}
# define BOARD_BATT_I_LIST {ADC_BATTERY1_CURRENT_CHANNEL, ADC_BATTERY2_CURRENT_CHANNEL, ADC_BATTERY3_CURRENT_CHANNEL, ADC_BATTERY4_CURRENT_CHANNEL}
# define BOARD_BRICK_VALID_LIST {BOARD_ADC_BRICK1_VALID, BOARD_ADC_BRICK2_VALID, BOARD_ADC_BRICK3_VALID, BOARD_ADC_BRICK4_VALID}
#else
# error Unsuported BOARD_NUMBER_BRICKS number.
#endif

View File

@ -105,7 +105,7 @@ private:
hrt_abstime _last_timestamp;
// Separate battery info publication because UavcanSensorBridgeBase only supports publishing one topic
uORB::PublicationMulti<battery_info_s> _battery_info_pub[battery_status_s::MAX_INSTANCES] {ORB_ID(battery_info), ORB_ID(battery_info), ORB_ID(battery_info), ORB_ID(battery_info)};
uORB::PublicationMulti<battery_info_s> _battery_info_pub[battery_status_s::MAX_INSTANCES] {ORB_ID(battery_info), ORB_ID(battery_info), ORB_ID(battery_info)};
battery_info_s _battery_info[battery_status_s::MAX_INSTANCES] {};
battery_status_s _battery_status[battery_status_s::MAX_INSTANCES] {};
@ -115,15 +115,13 @@ private:
static constexpr int BATTERY_INDEX_1 = 1;
static constexpr int BATTERY_INDEX_2 = 2;
static constexpr int BATTERY_INDEX_3 = 3;
static constexpr int BATTERY_INDEX_4 = 4;
static constexpr int SAMPLE_INTERVAL_US = 500_ms; // Typical message rate for a CAN battery monitor should be 2-5Hz.
static_assert(battery_status_s::MAX_INSTANCES <= BATTERY_INDEX_4, "Battery array too big");
static_assert(battery_status_s::MAX_INSTANCES <= BATTERY_INDEX_3, "Battery array too big");
Battery battery1 = {BATTERY_INDEX_1, this, SAMPLE_INTERVAL_US, battery_status_s::SOURCE_EXTERNAL};
Battery battery2 = {BATTERY_INDEX_2, this, SAMPLE_INTERVAL_US, battery_status_s::SOURCE_EXTERNAL};
Battery battery3 = {BATTERY_INDEX_3, this, SAMPLE_INTERVAL_US, battery_status_s::SOURCE_EXTERNAL};
Battery battery4 = {BATTERY_INDEX_4, this, SAMPLE_INTERVAL_US, battery_status_s::SOURCE_EXTERNAL};
Battery *_battery[battery_status_s::MAX_INSTANCES] = { &battery1, &battery2, &battery3, &battery4 };
Battery *_battery[battery_status_s::MAX_INSTANCES] = { &battery1, &battery2, &battery3};
};

View File

@ -685,7 +685,7 @@ private:
hrt_abstime _last_update_time{0};
float _update_rate_filtered{0};
PerBatteryData _batteries[battery_status_s::MAX_INSTANCES] {0, 1, 2, 3};
PerBatteryData _batteries[battery_status_s::MAX_INSTANCES] {0, 1, 2};
};
#endif // HIGH_LATENCY2_HPP