mirror of https://github.com/ArduPilot/ardupilot
AP_Periph: add AP_PERIPH_SAFTEY_SWITCH_ENABLED
This commit is contained in:
parent
1d4a77d33a
commit
ea207c4b4a
|
@ -68,6 +68,10 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#ifndef AP_PERIPH_SAFETY_SWITCH_ENABLED
|
||||
#define AP_PERIPH_SAFETY_SWITCH_ENABLED defined(HAL_PERIPH_ENABLE_RC_OUT)
|
||||
#endif
|
||||
|
||||
#include "Parameters.h"
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
|
|
|
@ -509,7 +509,7 @@ void AP_Periph_FW::handle_safety_state(CanardInstance* canard_instance, CanardRx
|
|||
return;
|
||||
}
|
||||
safety_state = req.status;
|
||||
#ifdef HAL_PERIPH_ENABLE_RC_OUT
|
||||
#if AP_PERIPH_SAFETY_SWITCH_ENABLED
|
||||
rcout_handle_safety_state(safety_state);
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -28,8 +28,12 @@ extern const AP_HAL::HAL &hal;
|
|||
|
||||
void AP_Periph_FW::rcout_init()
|
||||
{
|
||||
#if AP_PERIPH_SAFETY_SWITCH_ENABLED
|
||||
// start up with safety enabled. This disables the pwm output until we receive an packet from the rempte system
|
||||
hal.rcout->force_safety_on();
|
||||
#else
|
||||
hal.rcout->force_safety_off();
|
||||
#endif
|
||||
|
||||
#if HAL_WITH_ESC_TELEM && !HAL_GCS_ENABLED
|
||||
if (g.esc_telem_port >= 0) {
|
||||
|
|
Loading…
Reference in New Issue