APM_OBC: added heartbeat() method

this is used for when the plane is calibrating sensors, to ensure
heartbeat is continued to the failsafe board
This commit is contained in:
Andrew Tridgell 2014-09-24 11:03:19 +10:00
parent 1fa03a49c9
commit 5eee51b5a4
2 changed files with 23 additions and 0 deletions

View File

@ -259,6 +259,24 @@ APM_OBC::check(APM_OBC::control_mode mode, uint32_t last_heartbeat_ms, bool geof
}
}
// send heartbeat messages during sensor calibration
void
APM_OBC::heartbeat(void)
{
if (!_enable) {
return;
}
// if we are not terminating or if there is a separate terminate
// pin configured then toggle the heartbeat pin at 10Hz
if (_heartbeat_pin != -1 && (_terminate_pin != -1 || !_terminate)) {
_heartbeat_pin_value = !_heartbeat_pin_value;
hal.gpio->pinMode(_heartbeat_pin, HAL_GPIO_OUTPUT);
hal.gpio->write(_heartbeat_pin, _heartbeat_pin_value);
}
}
// check for altitude limit breach
bool
APM_OBC::check_altlimit(void)

View File

@ -64,8 +64,13 @@ public:
_saved_wp = 0;
}
// check that everything is OK
void check(enum control_mode control_mode, uint32_t last_heartbeat_ms, bool geofence_breached, uint32_t last_valid_rc_ms);
// generate heartbeat msgs, so external failsafe boards are happy
// during sensor calibration
void heartbeat(void);
// called in servo output code to set servos to crash position if needed
void check_crash_plane(void);