From 918218bdd4f1da35b29a680684f9852e8bf04353 Mon Sep 17 00:00:00 2001 From: Tatsuya Yamaguchi Date: Mon, 11 Oct 2021 15:19:53 +0900 Subject: [PATCH] Copter: fix compilation when ACRO, SPORT and DRIFT modes are disabled --- ArduCopter/Parameters.cpp | 2 ++ ArduCopter/Parameters.h | 3 +++ ArduCopter/tuning.cpp | 4 ++++ 3 files changed, 9 insertions(+) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index ae85157f2d..5cfe9b4a0c 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1075,7 +1075,9 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Range: 1 1080 // @User: Standard AP_GROUPINFO("ACRO_RP_RATE", 47, ParametersG2, acro_rp_rate, ACRO_RP_RATE_DEFAULT), +#endif +#if MODE_ACRO_ENABLED == ENABLED || MODE_DRIFT_ENABLED == ENABLED // @Param: ACRO_Y_RATE // @DisplayName: Acro Yaw Rate // @Description: Acro mode maximum yaw rate. Higher value means faster rate of rotation diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 611329ad93..cc9e60dde9 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -658,6 +658,9 @@ public: #if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED // Acro parameters AP_Float acro_rp_rate; +#endif + +#if MODE_ACRO_ENABLED == ENABLED || MODE_DRIFT_ENABLED == ENABLED AP_Float acro_y_rate; #endif diff --git a/ArduCopter/tuning.cpp b/ArduCopter/tuning.cpp index 9cb421c28e..f2bf8d8e1c 100644 --- a/ArduCopter/tuning.cpp +++ b/ArduCopter/tuning.cpp @@ -104,15 +104,19 @@ void Copter::tuning() wp_nav->set_speed_xy(tuning_value); break; +#if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED // Acro roll pitch rates case TUNING_ACRO_RP_RATE: g2.acro_rp_rate = tuning_value; break; +#endif +#if MODE_ACRO_ENABLED == ENABLED || MODE_DRIFT_ENABLED == ENABLED // Acro yaw rate case TUNING_ACRO_YAW_RATE: g2.acro_y_rate = tuning_value; break; +#endif #if FRAME_CONFIG == HELI_FRAME case TUNING_HELI_EXTERNAL_GYRO: