AP_BattMonitor: fix compile for AP_Periph

This commit is contained in:
Tom Pittenger 2020-11-20 21:25:59 -08:00 committed by Andrew Tridgell
parent 089f3aa349
commit 48e2b78cab
2 changed files with 11 additions and 3 deletions

View File

@ -296,11 +296,13 @@ AP_BattMonitor::read()
} }
} }
#ifndef HAL_BUILD_AP_PERIPH
AP_Logger *logger = AP_Logger::get_singleton(); AP_Logger *logger = AP_Logger::get_singleton();
if (logger->should_log(_log_battery_bit)) { if (logger != nullptr && logger->should_log(_log_battery_bit)) {
logger->Write_Current(); logger->Write_Current();
logger->Write_Power(); logger->Write_Power();
} }
#endif
check_failsafes(); check_failsafes();
@ -411,10 +413,12 @@ void AP_BattMonitor::check_failsafes(void)
break; break;
} }
gcs().send_text(MAV_SEVERITY_WARNING, "Battery %d is %s %.2fV used %.0f mAh", i + 1, type_str, GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Battery %d is %s %.2fV used %.0f mAh", i + 1, type_str,
(double)voltage(i), (double)state[i].consumed_mah); (double)voltage(i), (double)state[i].consumed_mah);
_has_triggered_failsafe = true; _has_triggered_failsafe = true;
#ifndef HAL_BUILD_AP_PERIPH
AP_Notify::flags.failsafe_battery = true; AP_Notify::flags.failsafe_battery = true;
#endif
state[i].failsafe = type; state[i].failsafe = type;
// map the desired failsafe action to a prioritiy level // map the desired failsafe action to a prioritiy level
@ -520,15 +524,19 @@ void AP_BattMonitor::checkPoweringOff(void)
{ {
for (uint8_t i = 0; i < _num_instances; i++) { for (uint8_t i = 0; i < _num_instances; i++) {
if (state[i].is_powering_off && !state[i].powerOffNotified) { if (state[i].is_powering_off && !state[i].powerOffNotified) {
#ifndef HAL_BUILD_AP_PERIPH
// Set the AP_Notify flag, which plays the power off tones // Set the AP_Notify flag, which plays the power off tones
AP_Notify::flags.powering_off = true; AP_Notify::flags.powering_off = true;
#endif
// Send a Mavlink broadcast announcing the shutdown // Send a Mavlink broadcast announcing the shutdown
#ifndef HAL_NO_GCS
mavlink_command_long_t cmd_msg{}; mavlink_command_long_t cmd_msg{};
cmd_msg.command = MAV_CMD_POWER_OFF_INITIATED; cmd_msg.command = MAV_CMD_POWER_OFF_INITIATED;
cmd_msg.param1 = i+1; cmd_msg.param1 = i+1;
GCS_MAVLINK::send_to_components(MAVLINK_MSG_ID_COMMAND_LONG, (char*)&cmd_msg, sizeof(cmd_msg)); GCS_MAVLINK::send_to_components(MAVLINK_MSG_ID_COMMAND_LONG, (char*)&cmd_msg, sizeof(cmd_msg));
gcs().send_text(MAV_SEVERITY_WARNING, "Vehicle %d battery %d is powering off", mavlink_system.sysid, i+1); gcs().send_text(MAV_SEVERITY_WARNING, "Vehicle %d battery %d is powering off", mavlink_system.sysid, i+1);
#endif
// only send this once // only send this once
state[i].powerOffNotified = true; state[i].powerOffNotified = true;

View File

@ -70,7 +70,7 @@ void AP_BattMonitor_FuelFlow::read()
last_pin, last_pin,
FUNCTOR_BIND_MEMBER(&AP_BattMonitor_FuelFlow::irq_handler, void, uint8_t, bool, uint32_t), FUNCTOR_BIND_MEMBER(&AP_BattMonitor_FuelFlow::irq_handler, void, uint8_t, bool, uint32_t),
AP_HAL::GPIO::INTERRUPT_RISING)) { AP_HAL::GPIO::INTERRUPT_RISING)) {
gcs().send_text(MAV_SEVERITY_WARNING, "FuelFlow: Failed to attach to pin %u", last_pin); GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "FuelFlow: Failed to attach to pin %u", last_pin);
} }
} }
} }