mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Corrected battery monitoring in apo.
This commit is contained in:
parent
9e9da38c67
commit
986fca3116
@ -127,7 +127,7 @@ public:
|
||||
_mode = MAV_MODE_FAILSAFE;
|
||||
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("configure gcs to send heartbeat"));
|
||||
// if battery less than 5%, go to failsafe
|
||||
} else if (_hal->batteryMonitor->getPercentage() < 5) {
|
||||
} else if (_hal->batteryMonitor && _hal->batteryMonitor->getPercentage() < 5) {
|
||||
_mode = MAV_MODE_FAILSAFE;
|
||||
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("recharge battery"));
|
||||
// manual/auto switch
|
||||
|
@ -211,10 +211,10 @@ void AP_Autopilot::callback2(void * data) {
|
||||
if (apo->getHal()->gcs) {
|
||||
// send messages
|
||||
apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_GPS_RAW);
|
||||
//apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_RC_CHANNELS_SCALED);
|
||||
apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_RC_CHANNELS_SCALED);
|
||||
apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_RC_CHANNELS_RAW);
|
||||
//apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_GLOBAL_POSITION);
|
||||
//apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_RC_CHANNELS_RAW);
|
||||
//apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_SCALED_IMU);
|
||||
apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_SCALED_IMU);
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user