mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: send heartbeat to AFS when calibrating sensors
This commit is contained in:
parent
5eee51b5a4
commit
4b01cee330
@ -280,6 +280,11 @@ static struct {
|
|||||||
// should throttle be pass-thru in guided?
|
// should throttle be pass-thru in guided?
|
||||||
static bool guided_throttle_passthru;
|
static bool guided_throttle_passthru;
|
||||||
|
|
||||||
|
// are we doing calibration? This is used to allow heartbeat to
|
||||||
|
// external failsafe boards during baro and airspeed calibration
|
||||||
|
static bool in_calibration;
|
||||||
|
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
// GCS selection
|
// GCS selection
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
|
@ -984,10 +984,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
packet.param2 == 1) {
|
packet.param2 == 1) {
|
||||||
startup_INS_ground(true);
|
startup_INS_ground(true);
|
||||||
} else if (packet.param3 == 1) {
|
} else if (packet.param3 == 1) {
|
||||||
|
in_calibration = true;
|
||||||
init_barometer();
|
init_barometer();
|
||||||
if (airspeed.enabled()) {
|
if (airspeed.enabled()) {
|
||||||
zero_airspeed();
|
zero_airspeed();
|
||||||
}
|
}
|
||||||
|
in_calibration = false;
|
||||||
}
|
}
|
||||||
if (packet.param4 == 1) {
|
if (packet.param4 == 1) {
|
||||||
trim_radio();
|
trim_radio();
|
||||||
|
@ -39,6 +39,14 @@ void failsafe_check(void)
|
|||||||
if (in_failsafe && tnow - last_timestamp > 20000) {
|
if (in_failsafe && tnow - last_timestamp > 20000) {
|
||||||
last_timestamp = tnow;
|
last_timestamp = tnow;
|
||||||
|
|
||||||
|
#if OBC_FAILSAFE == ENABLED
|
||||||
|
if (in_calibration) {
|
||||||
|
// tell the failsafe system that we are calibrating
|
||||||
|
// sensors, so don't trigger failsafe
|
||||||
|
obc.heartbeat();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
if (hal.rcin->num_channels() == 0) {
|
if (hal.rcin->num_channels() == 0) {
|
||||||
// we don't have any RC input to pass through
|
// we don't have any RC input to pass through
|
||||||
return;
|
return;
|
||||||
|
Loading…
Reference in New Issue
Block a user