Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_BattMonitor: ESC: add mask parameter #27030

Merged
merged 1 commit into from
May 13, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
32 changes: 32 additions & 0 deletions libraries/AP_BattMonitor/AP_BattMonitor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
// @Path: AP_BattMonitor_Synthetic_Current.cpp
// @Group: _
// @Path: AP_BattMonitor_INA2xx.cpp
// @Group: _
// @Path: AP_BattMonitor_ESC.cpp
AP_SUBGROUPVARPTR(drivers[0], "_", 41, AP_BattMonitor, backend_var_info[0]),

#if AP_BATT_MONITOR_MAX_INSTANCES > 1
Expand All @@ -87,6 +89,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
// @Path: AP_BattMonitor_Synthetic_Current.cpp
// @Group: 2_
// @Path: AP_BattMonitor_INA2xx.cpp
// @Group: 2_
// @Path: AP_BattMonitor_ESC.cpp
AP_SUBGROUPVARPTR(drivers[1], "2_", 42, AP_BattMonitor, backend_var_info[1]),
#endif

Expand All @@ -109,6 +113,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
// @Path: AP_BattMonitor_Synthetic_Current.cpp
// @Group: 3_
// @Path: AP_BattMonitor_INA2xx.cpp
// @Group: 3_
// @Path: AP_BattMonitor_ESC.cpp
AP_SUBGROUPVARPTR(drivers[2], "3_", 43, AP_BattMonitor, backend_var_info[2]),
#endif

Expand All @@ -131,6 +137,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
// @Path: AP_BattMonitor_Synthetic_Current.cpp
// @Group: 4_
// @Path: AP_BattMonitor_INA2xx.cpp
// @Group: 4_
// @Path: AP_BattMonitor_ESC.cpp
AP_SUBGROUPVARPTR(drivers[3], "4_", 44, AP_BattMonitor, backend_var_info[3]),
#endif

Expand All @@ -153,6 +161,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
// @Path: AP_BattMonitor_Synthetic_Current.cpp
// @Group: 5_
// @Path: AP_BattMonitor_INA2xx.cpp
// @Group: 5_
// @Path: AP_BattMonitor_ESC.cpp
AP_SUBGROUPVARPTR(drivers[4], "5_", 45, AP_BattMonitor, backend_var_info[4]),
#endif

Expand All @@ -175,6 +185,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
// @Path: AP_BattMonitor_Synthetic_Current.cpp
// @Group: 6_
// @Path: AP_BattMonitor_INA2xx.cpp
// @Group: 6_
// @Path: AP_BattMonitor_ESC.cpp
AP_SUBGROUPVARPTR(drivers[5], "6_", 46, AP_BattMonitor, backend_var_info[5]),
#endif

Expand All @@ -197,6 +209,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
// @Path: AP_BattMonitor_Synthetic_Current.cpp
// @Group: 7_
// @Path: AP_BattMonitor_INA2xx.cpp
// @Group: 7_
// @Path: AP_BattMonitor_ESC.cpp
AP_SUBGROUPVARPTR(drivers[6], "7_", 47, AP_BattMonitor, backend_var_info[6]),
#endif

Expand All @@ -219,6 +233,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
// @Path: AP_BattMonitor_Synthetic_Current.cpp
// @Group: 8_
// @Path: AP_BattMonitor_INA2xx.cpp
// @Group: 8_
// @Path: AP_BattMonitor_ESC.cpp
AP_SUBGROUPVARPTR(drivers[7], "8_", 48, AP_BattMonitor, backend_var_info[7]),
#endif

Expand All @@ -241,6 +257,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
// @Path: AP_BattMonitor_Synthetic_Current.cpp
// @Group: 9_
// @Path: AP_BattMonitor_INA2xx.cpp
// @Group: 9_
// @Path: AP_BattMonitor_ESC.cpp
AP_SUBGROUPVARPTR(drivers[8], "9_", 49, AP_BattMonitor, backend_var_info[8]),
#endif

Expand All @@ -263,6 +281,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
// @Path: AP_BattMonitor_Synthetic_Current.cpp
// @Group: A_
// @Path: AP_BattMonitor_INA2xx.cpp
// @Group: A_
// @Path: AP_BattMonitor_ESC.cpp
AP_SUBGROUPVARPTR(drivers[9], "A_", 50, AP_BattMonitor, backend_var_info[9]),
#endif

Expand All @@ -285,6 +305,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
// @Path: AP_BattMonitor_Synthetic_Current.cpp
// @Group: B_
// @Path: AP_BattMonitor_INA2xx.cpp
// @Group: B_
// @Path: AP_BattMonitor_ESC.cpp
AP_SUBGROUPVARPTR(drivers[10], "B_", 51, AP_BattMonitor, backend_var_info[10]),
#endif

Expand All @@ -307,6 +329,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
// @Path: AP_BattMonitor_Synthetic_Current.cpp
// @Group: C_
// @Path: AP_BattMonitor_INA2xx.cpp
// @Group: C_
// @Path: AP_BattMonitor_ESC.cpp
AP_SUBGROUPVARPTR(drivers[11], "C_", 52, AP_BattMonitor, backend_var_info[11]),
#endif

Expand All @@ -329,6 +353,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
// @Path: AP_BattMonitor_Synthetic_Current.cpp
// @Group: D_
// @Path: AP_BattMonitor_INA2xx.cpp
// @Group: D_
// @Path: AP_BattMonitor_ESC.cpp
AP_SUBGROUPVARPTR(drivers[12], "D_", 53, AP_BattMonitor, backend_var_info[12]),
#endif

Expand All @@ -351,6 +377,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
// @Path: AP_BattMonitor_Synthetic_Current.cpp
// @Group: E_
// @Path: AP_BattMonitor_INA2xx.cpp
// @Group: E_
// @Path: AP_BattMonitor_ESC.cpp
AP_SUBGROUPVARPTR(drivers[13], "E_", 54, AP_BattMonitor, backend_var_info[13]),
#endif

Expand All @@ -373,6 +401,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
// @Path: AP_BattMonitor_Synthetic_Current.cpp
// @Group: F_
// @Path: AP_BattMonitor_INA2xx.cpp
// @Group: F_
// @Path: AP_BattMonitor_ESC.cpp
AP_SUBGROUPVARPTR(drivers[14], "F_", 55, AP_BattMonitor, backend_var_info[14]),
#endif

Expand All @@ -395,6 +425,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
// @Path: AP_BattMonitor_Synthetic_Current.cpp
// @Group: G_
// @Path: AP_BattMonitor_INA2xx.cpp
// @Group: G_
// @Path: AP_BattMonitor_ESC.cpp
AP_SUBGROUPVARPTR(drivers[15], "G_", 56, AP_BattMonitor, backend_var_info[15]),
#endif

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ const AP_Param::GroupInfo AP_BattMonitor_DroneCAN::var_info[] = {
// @User: Advanced
AP_GROUPINFO("CURR_MULT", 30, AP_BattMonitor_DroneCAN, _curr_mult, 1.0),

// Param indexes must be between 30 and 39 to avoid conflict with other battery monitor param tables loaded by pointer
// Param indexes must be between 30 and 35 to avoid conflict with other battery monitor param tables loaded by pointer

AP_GROUPEND
};
Expand Down
34 changes: 33 additions & 1 deletion libraries/AP_BattMonitor/AP_BattMonitor_ESC.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,32 @@

#include "AP_BattMonitor_ESC.h"

const AP_Param::GroupInfo AP_BattMonitor_ESC::var_info[] = {

// Param indexes must be between 36 and 39 to avoid conflict with other battery monitor param tables loaded by pointer

// @Param: ESC_MASK
// @DisplayName: ESC mask
// @Description: If 0 all connected ESCs will be used. If non-zero, only those selected in will be used.
// @Bitmask: 0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16, 16: ESC 17, 17: ESC 18, 18: ESC 19, 19: ESC 20, 20: ESC 21, 21: ESC 22, 22: ESC 23, 23: ESC 24, 24: ESC 25, 25: ESC 26, 26: ESC 27, 27: ESC 28, 28: ESC 29, 29: ESC 30, 30: ESC 31, 31: ESC 32
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I know we go up to 32 bits on here and likely elsewhere but in reality we should only go up to 24 due to float-integer roundoff error.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We use the full 32 bits for all servo stuff.

// @User: Standard
AP_GROUPINFO("ESC_MASK", 36, AP_BattMonitor_ESC, _mask, 0),

// Param indexes must be between 36 and 39 to avoid conflict with other battery monitor param tables loaded by pointer

AP_GROUPEND
};

// constructor. This incorporates initialisation as well.
AP_BattMonitor_ESC::AP_BattMonitor_ESC(AP_BattMonitor &mon,
AP_BattMonitor::BattMonitor_State &mon_state,
AP_BattMonitor_Params &params):
AP_BattMonitor_Backend(mon, mon_state, params)
{
AP_Param::setup_object_defaults(this, var_info);
_state.var_info = var_info;
};

void AP_BattMonitor_ESC::init(void)
{
}
Expand All @@ -34,9 +60,15 @@ void AP_BattMonitor_ESC::read(void)
float current_sum = 0;
float temperature_sum = 0;
uint32_t highest_ms = 0;
_state.consumed_mah = delta_mah;
_state.consumed_mah = delta_mah;

const bool all_enabled = _mask == 0;
for (uint8_t i=0; i<ESC_TELEM_MAX_ESCS; i++) {
if (!all_enabled && ((_mask & (1U<<i)) == 0)) {
// Only include ESCs set in mask
continue;
}

int16_t temperature_cdeg;
float voltage;
float current;
Expand Down
9 changes: 6 additions & 3 deletions libraries/AP_BattMonitor/AP_BattMonitor_ESC.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,7 @@ class AP_BattMonitor_ESC :public AP_BattMonitor_Backend
{
public:
// constructor. This incorporates initialisation as well.
AP_BattMonitor_ESC(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params &params):
AP_BattMonitor_Backend(mon, mon_state, params)
{};
AP_BattMonitor_ESC(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params &params);

virtual ~AP_BattMonitor_ESC(void) {};

Expand All @@ -46,7 +44,12 @@ class AP_BattMonitor_ESC :public AP_BattMonitor_Backend
// reset remaining percentage to given value
virtual bool reset_remaining(float percentage) override;

static const struct AP_Param::GroupInfo var_info[];

private:

AP_Int32 _mask;

bool have_current;
bool have_temperature;
float delta_mah;
Expand Down
Loading