mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
OBC: added FS_TERM_PIN option
this sets a pin for flight termination
This commit is contained in:
parent
164c60d25f
commit
13145e4c01
@ -49,6 +49,12 @@ const AP_Param::GroupInfo APM_OBC::var_info[] PROGMEM = {
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("TERM_ACTION", 6, APM_OBC, _terminate_action, 0),
|
||||
|
||||
// @Param: TERM_PIN
|
||||
// @DisplayName: Terminate Pin
|
||||
// @Description: This sets a digital output pin to set high on flight termination
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("TERM_PIN", 7, APM_OBC, _terminate_pin, -1),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
@ -169,4 +175,13 @@ APM_OBC::check(APM_OBC::control_mode mode,
|
||||
_heartbeat_pin_value = !_heartbeat_pin_value;
|
||||
digitalWrite(_heartbeat_pin, _heartbeat_pin_value);
|
||||
}
|
||||
|
||||
// set the terminate pin
|
||||
if (_terminate_pin != -1) {
|
||||
if (_terminate_pin != _last_terminate_pin) {
|
||||
pinMode(_terminate_pin, OUTPUT);
|
||||
_last_terminate_pin = _terminate_pin;
|
||||
}
|
||||
digitalWrite(_terminate_pin, _terminate?HIGH:LOW);
|
||||
}
|
||||
}
|
||||
|
@ -65,12 +65,14 @@ private:
|
||||
// digital output pins for communicating with the failsafe board
|
||||
AP_Int8 _heartbeat_pin;
|
||||
AP_Int8 _manual_pin;
|
||||
AP_Int8 _terminate_pin;
|
||||
AP_Int8 _terminate;
|
||||
AP_Int8 _terminate_action;
|
||||
|
||||
// last pins to cope with changing at runtime
|
||||
int8_t _last_heartbeat_pin;
|
||||
int8_t _last_manual_pin;
|
||||
int8_t _last_terminate_pin;
|
||||
|
||||
// waypoint numbers to jump to on failsafe conditions
|
||||
AP_Int8 _wp_comms_hold;
|
||||
|
Loading…
Reference in New Issue
Block a user