Copter: fix compilation when ACRO, SPORT and DRIFT modes are disabled

This commit is contained in:
Tatsuya Yamaguchi 2021-10-11 15:19:53 +09:00 committed by Peter Barker
parent aa4f375015
commit 918218bdd4
3 changed files with 9 additions and 0 deletions

View File

@ -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

View File

@ -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

View File

@ -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: