From c30af1b0439d9fa2e35ce33a28316a0a55796ade Mon Sep 17 00:00:00 2001 From: Michael Day <michael.day@gtri.gatech.edu> Date: Sat, 19 Nov 2016 13:55:18 -0500 Subject: [PATCH] Copter: Ignore some checks in SITL to get faster takeoff --- ArduCopter/arming_checks.cpp | 2 ++ ArduCopter/ekf_check.cpp | 4 ++++ ArduCopter/events.cpp | 3 +++ ArduCopter/flight_mode.cpp | 3 +++ 4 files changed, 12 insertions(+) diff --git a/ArduCopter/arming_checks.cpp b/ArduCopter/arming_checks.cpp index 8a7d25700c..6369c68414 100644 --- a/ArduCopter/arming_checks.cpp +++ b/ArduCopter/arming_checks.cpp @@ -500,6 +500,7 @@ bool Copter::pre_arm_gps_checks(bool display_failure) return true; } +#if CONFIG_HAL_BOARD != HAL_BOARD_SITL // ensure GPS is ok if (!position_ok()) { if (display_failure) { @@ -525,6 +526,7 @@ bool Copter::pre_arm_gps_checks(bool display_failure) } return false; } +#endif // check home and EKF origin are not too far if (far_from_EKF_origin(ahrs.get_home())) { diff --git a/ArduCopter/ekf_check.cpp b/ArduCopter/ekf_check.cpp index 5a20710303..3ef5843c62 100644 --- a/ArduCopter/ekf_check.cpp +++ b/ArduCopter/ekf_check.cpp @@ -28,6 +28,10 @@ static struct { // should be called at 10hz void Copter::ekf_check() { +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + return; +#endif + // exit immediately if ekf has no origin yet - this assumes the origin can never become unset Location temp_loc; if (!ahrs.get_origin(temp_loc)) { diff --git a/ArduCopter/events.cpp b/ArduCopter/events.cpp index 2a713e61c4..2ab59a49a2 100644 --- a/ArduCopter/events.cpp +++ b/ArduCopter/events.cpp @@ -171,6 +171,9 @@ void Copter::failsafe_terrain_set_status(bool data_ok) // terrain failsafe action void Copter::failsafe_terrain_on_event() { +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + return; +#endif failsafe.terrain = true; gcs_send_text(MAV_SEVERITY_CRITICAL,"Failsafe: Terrain data missing"); Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_TERRAIN, ERROR_CODE_FAILSAFE_OCCURRED); diff --git a/ArduCopter/flight_mode.cpp b/ArduCopter/flight_mode.cpp index 9e7b3de2a0..7df1a3a3c4 100644 --- a/ArduCopter/flight_mode.cpp +++ b/ArduCopter/flight_mode.cpp @@ -14,6 +14,9 @@ bool Copter::set_mode(control_mode_t mode, mode_reason_t reason) // boolean to record if flight mode could be set bool success = false; bool ignore_checks = !motors.armed(); // allow switching to any mode if disarmed. We rely on the arming check to perform +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + ignore_checks = true; +#endif // return immediately if we are already in the desired mode if (mode == control_mode) { -- GitLab