diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index bc6d28fbfa..973478239b 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -559,7 +559,7 @@ void Plane::update_alt() // low pass the sink rate to take some of the noise out auto_state.sink_rate = 0.8f * auto_state.sink_rate + 0.2f*sink_rate; -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED parachute.set_sink_rate(auto_state.sink_rate); #endif diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index d77210f7ac..eaa1976f62 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1054,7 +1054,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in case MAV_CMD_DO_CHANGE_SPEED: return handle_command_DO_CHANGE_SPEED(packet); -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED case MAV_CMD_DO_PARACHUTE: return handle_MAV_CMD_DO_PARACHUTE(packet); #endif @@ -1182,7 +1182,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_AUTOTUNE_ENABLE(const mavlink_co return MAV_RESULT_ACCEPTED; } -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet) { // configure or release parachute diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index cc6bc6e6ee..ead102ef7a 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -782,7 +782,7 @@ const AP_Param::Info Plane::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/ArduPlane/Plane.h b/ArduPlane/Plane.h index 4a78dd32e9..11c151811e 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -649,7 +649,7 @@ private: FUNCTOR_BIND_MEMBER(&Plane::exit_mission_callback, void)}; -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED AP_Parachute parachute; #endif @@ -1155,7 +1155,7 @@ private: // parachute.cpp void parachute_check(); -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED void do_parachute(const AP_Mission::Mission_Command& cmd); void parachute_release(); bool parachute_manual_release(); diff --git a/ArduPlane/RC_Channel.cpp b/ArduPlane/RC_Channel.cpp index 9230792084..cd1d63e04a 100644 --- a/ArduPlane/RC_Channel.cpp +++ b/ArduPlane/RC_Channel.cpp @@ -353,7 +353,7 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch break; case AUX_FUNC::PARACHUTE_RELEASE: -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED if (ch_flag == AuxSwitchPos::HIGH) { plane.parachute_manual_release(); } diff --git a/ArduPlane/config.h b/ArduPlane/config.h index 08917cbe58..0ba606c357 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -213,12 +213,6 @@ # define FENCE_TRIGGERED_PIN -1 #endif -////////////////////////////////////////////////////////////////////////////// -// Parachute release -#ifndef PARACHUTE -#define PARACHUTE HAL_PARACHUTE_ENABLED -#endif - #ifndef OFFBOARD_GUIDED #define OFFBOARD_GUIDED 1 #endif diff --git a/ArduPlane/events.cpp b/ArduPlane/events.cpp index 12abb98e3b..64127c633c 100644 --- a/ArduPlane/events.cpp +++ b/ArduPlane/events.cpp @@ -138,7 +138,7 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason break; } if(g.fs_action_long == FS_ACTION_LONG_PARACHUTE) { -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED parachute_release(); #endif } else if (g.fs_action_long == FS_ACTION_LONG_GLIDE) { @@ -187,7 +187,7 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason case Mode::Number::GUIDED: if(g.fs_action_long == FS_ACTION_LONG_PARACHUTE) { -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED parachute_release(); #endif } else if (g.fs_action_long == FS_ACTION_LONG_GLIDE) { @@ -311,7 +311,7 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action) break; case Failsafe_Action_Parachute: -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED parachute_release(); #endif break; diff --git a/ArduPlane/is_flying.cpp b/ArduPlane/is_flying.cpp index 979a640a69..7118f352fe 100644 --- a/ArduPlane/is_flying.cpp +++ b/ArduPlane/is_flying.cpp @@ -162,7 +162,7 @@ void Plane::update_is_flying_5Hz(void) #if HAL_ADSB_ENABLED adsb.set_is_flying(new_is_flying); #endif -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED parachute.set_is_flying(new_is_flying); #endif #if AP_STATS_ENABLED diff --git a/ArduPlane/parachute.cpp b/ArduPlane/parachute.cpp index 61cec7ae0a..7023d33711 100644 --- a/ArduPlane/parachute.cpp +++ b/ArduPlane/parachute.cpp @@ -6,13 +6,13 @@ */ void Plane::parachute_check() { -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED parachute.update(); parachute.check_sink_rate(); #endif } -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED /* parachute_release - trigger the release of the parachute diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 4f7b1c4450..aa2c7ce373 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -78,7 +78,7 @@ bool Plane::suppress_throttle(void) return false; } -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED if (control_mode->does_auto_throttle() && parachute.release_initiated()) { // throttle always suppressed in auto-throttle modes after parachute release initiated throttle_suppressed = true;