Skip to content

Commit

Permalink
AP_BattMonitor: Add architecture to shutdown batteries
Browse files Browse the repository at this point in the history
  • Loading branch information
IanBurwell committed Jul 11, 2024
1 parent 91b2d0d commit 913c469
Show file tree
Hide file tree
Showing 4 changed files with 90 additions and 2 deletions.
62 changes: 62 additions & 0 deletions libraries/AP_BattMonitor/AP_BattMonitor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1176,6 +1176,68 @@ bool AP_BattMonitor::handle_scripting(uint8_t idx, const BattMonitorScript_State
}
#endif

// Returns true if the battery has shutdown functionality
bool AP_BattMonitor::can_shutdown(uint8_t instance) const
{
if (instance >= AP_BATT_MONITOR_MAX_INSTANCES || drivers[instance] == nullptr) {
return false;
}

return drivers[instance]->can_shutdown();
}

// Returns true if all connected batteries have shutdown functionality
bool AP_BattMonitor::can_shutdown() const
{
if (_num_instances == 0) {
return false;
}

for (uint8_t i=0; i< _num_instances; i++) {
if (configured_type(i) != Type::NONE && !can_shutdown(i)) {
return false;
}
}

return true;
}

// Attempts to shut down a battery (if supported)
bool AP_BattMonitor::shutdown(uint8_t instance)
{
if (instance >= AP_BATT_MONITOR_MAX_INSTANCES || drivers[instance] == nullptr) {
return false;
}

if (configured_type(instance) == Type::NONE) {
return true;
}

return drivers[instance]->shutdown();
}

// Attempts to shut down all batteries that support doing so
bool AP_BattMonitor::shutdown()
{
if (!can_shutdown() || _num_instances == 0) {
return false;
}

for (uint8_t i=0; i< _num_instances; i++) {
// Save primary battery for last
if (i == AP_BATT_PRIMARY_INSTANCE) {
continue;
}

if (!shutdown(i)) {
return false;
}
}

return shutdown(AP_BATT_PRIMARY_INSTANCE);
}


namespace AP {

AP_BattMonitor &battery()
Expand Down
9 changes: 9 additions & 0 deletions libraries/AP_BattMonitor/AP_BattMonitor.h
Original file line number Diff line number Diff line change
Expand Up @@ -275,6 +275,15 @@ class AP_BattMonitor
// sends powering off mavlink broadcasts and sets notify flag
void checkPoweringOff(void);

// returns true if all connected batteries can be shutdown by the AP
bool can_shutdown(void) const;
// returns true if the battery has the capability to be shutdown by the AP
bool can_shutdown(uint8_t instance) const;
// attempts to shut down all batteries that support doing so
bool shutdown(void);
// attempts to shut down a battery (if supported)
bool shutdown(uint8_t instance);

// reset battery remaining percentage
bool reset_remaining_mask(uint16_t battery_mask, float percentage);
bool reset_remaining(uint8_t instance, float percentage) { return reset_remaining_mask(1U<<instance, percentage);}
Expand Down
7 changes: 6 additions & 1 deletion libraries/AP_BattMonitor/AP_BattMonitor_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -85,13 +85,18 @@ class AP_BattMonitor_Backend
// return mavlink fault bitmask (see MAV_BATTERY_FAULT enum)
virtual uint32_t get_mavlink_fault_bitmask() const { return 0; }

// logging functions
// logging functions
void Log_Write_BAT(const uint8_t instance, const uint64_t time_us) const;
void Log_Write_BCL(const uint8_t instance, const uint64_t time_us) const;

// set desired MPPT powered state (enabled/disabled)
virtual void mppt_set_powered_state(bool power_on) {};

// returns true if the battery can be shutdown with shutdown()
virtual bool can_shutdown() { return false; };
// shuts the battery down if supported
virtual bool shutdown() { return false; };

// Update an ESC telemetry channel's power information
void update_esc_telem_outbound();

Expand Down
14 changes: 13 additions & 1 deletion libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3389,7 +3389,7 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_int_t &pac
#endif
}

// refuse reboot when armed:
// refuse shutdown/reboot when armed:
if (hal.util->get_soft_armed()) {
/// but allow it if forced:
const uint32_t magic_force_reboot_value = 20190226;
Expand All @@ -3398,6 +3398,18 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_int_t &pac
}
}

#if AP_BATTERY_ENABLED
// Check if shutdown is requested
if (is_equal(packet.param1, 2.0f)) {
// If the battery monitor in use doesn't support shutdown
if (!AP::battery().shutdown()){
return MAV_RESULT_FAILED;
}

return MAV_RESULT_ACCEPTED;
}
#endif

if (!(is_equal(packet.param1, 1.0f) || is_equal(packet.param1, 3.0f))) {
// param1 must be 1 or 3 - 1 being reboot, 3 being reboot-to-bootloader
return MAV_RESULT_UNSUPPORTED;
Expand Down

0 comments on commit 913c469

Please sign in to comment.