diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index 69a59ef0d8..0f1bee348f 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -4,7 +4,6 @@ //#define LOGGING_ENABLED DISABLED // disable logging to save 11K of flash space //#define MOUNT DISABLED // disable the camera gimbal to save 8K of flash space //#define AUTOTUNE_ENABLED DISABLED // disable the auto tune functionality to save 7k of flash -//#define PARACHUTE DISABLED // disable parachute release to save 1k of flash //#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands //#define MODE_ACRO_ENABLED DISABLED // disable acrobatic mode support //#define MODE_AUTO_ENABLED DISABLED // disable auto mode support diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index fcda06e571..5fe4d3ee9e 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -521,7 +521,7 @@ private: #endif // Parachute release -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED AP_Parachute parachute; #endif diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index d64cad0d2d..a81ed5a46e 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -795,7 +795,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i case MAV_CMD_NAV_VTOL_TAKEOFF: return handle_MAV_CMD_NAV_TAKEOFF(packet); -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED case MAV_CMD_DO_PARACHUTE: return handle_MAV_CMD_DO_PARACHUTE(packet); #endif @@ -973,7 +973,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_MISSION_START(const mavlink_comman -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet) { // configure or release parachute diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 105b660a8e..f0e3d6f725 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -453,7 +453,7 @@ const AP_Param::Info Copter::var_info[] = { GOBJECT(relay, "RELAY", AP_Relay), #endif -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED // @Group: CHUTE_ // @Path: ../libraries/AP_Parachute/AP_Parachute.cpp GOBJECT(parachute, "CHUTE_", AP_Parachute), diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index c62f8b6d2b..e0cf6905d3 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -312,7 +312,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc do_aux_function_change_mode(Mode::Number::FOLLOW, ch_flag); break; -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED case AUX_FUNC::PARACHUTE_ENABLE: // Parachute enable/disable copter.parachute.enabled(ch_flag == AuxSwitchPos::HIGH); diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 682d2e1c6c..17b0564c99 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -120,12 +120,6 @@ # define AUTOTUNE_ENABLED ENABLED #endif -////////////////////////////////////////////////////////////////////////////// -// Parachute release -#ifndef PARACHUTE - # define PARACHUTE HAL_PARACHUTE_ENABLED -#endif - ////////////////////////////////////////////////////////////////////////////// // Nav-Guided - allows external nav computer to control vehicle #ifndef AC_NAV_GUIDED diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index 6383636f3c..ad3383723e 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -229,7 +229,7 @@ void Copter::yaw_imbalance_check() } } -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED // Code to detect a crash main ArduCopter code #define PARACHUTE_CHECK_TRIGGER_SEC 1 // 1 second of loss of control triggers the parachute @@ -369,4 +369,4 @@ void Copter::parachute_manual_release() parachute_release(); } -#endif // PARACHUTE == ENABLED +#endif // HAL_PARACHUTE_ENABLED diff --git a/ArduCopter/land_detector.cpp b/ArduCopter/land_detector.cpp index ee56446a3a..234888420e 100644 --- a/ArduCopter/land_detector.cpp +++ b/ArduCopter/land_detector.cpp @@ -22,7 +22,7 @@ void Copter::update_land_and_crash_detectors() update_land_detector(); -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED // check parachute parachute_check(); #endif diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 3dde86df7d..11b2a64410 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -653,7 +653,7 @@ private: void do_set_home(const AP_Mission::Mission_Command& cmd); void do_roi(const AP_Mission::Mission_Command& cmd); void do_mount_control(const AP_Mission::Mission_Command& cmd); -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED void do_parachute(const AP_Mission::Mission_Command& cmd); #endif #if AP_WINCH_ENABLED