|
|
|
@ -73,9 +73,10 @@ bool PX4Util::run_debug_shell(AP_HAL::BetterStream *stream)
@@ -73,9 +73,10 @@ bool PX4Util::run_debug_shell(AP_HAL::BetterStream *stream)
|
|
|
|
|
*/ |
|
|
|
|
enum PX4Util::safety_state PX4Util::safety_switch_state(void) |
|
|
|
|
{ |
|
|
|
|
#ifdef CONFIG_ARCH_BOARD_AEROFC_V1 |
|
|
|
|
#if !HAL_HAVE_SAFETY_SWITCH |
|
|
|
|
return AP_HAL::Util::SAFETY_NONE; |
|
|
|
|
#else |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
if (_safety_handle == -1) { |
|
|
|
|
_safety_handle = orb_subscribe(ORB_ID(safety)); |
|
|
|
|
} |
|
|
|
@ -93,7 +94,6 @@ enum PX4Util::safety_state PX4Util::safety_switch_state(void)
@@ -93,7 +94,6 @@ enum PX4Util::safety_state PX4Util::safety_switch_state(void)
|
|
|
|
|
return AP_HAL::Util::SAFETY_ARMED; |
|
|
|
|
} |
|
|
|
|
return AP_HAL::Util::SAFETY_DISARMED; |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void PX4Util::set_system_clock(uint64_t time_utc_usec) |
|
|
|
|