mirror of https://github.com/ArduPilot/ardupilot
Copter: remove more parameters when ACRO is disabled
This commit is contained in:
parent
d78c2a1015
commit
5f9879fae1
|
@ -212,7 +212,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
|
|||
}
|
||||
|
||||
// acro balance parameter check
|
||||
#if MODE_ACRO_ENABLED == ENABLED
|
||||
#if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED
|
||||
if ((copter.g.acro_balance_roll > copter.attitude_control->get_angle_roll_p().kP()) || (copter.g.acro_balance_pitch > copter.attitude_control->get_angle_pitch_p().kP())) {
|
||||
if (display_failure) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: ACRO_BAL_ROLL/PITCH");
|
||||
|
|
|
@ -526,9 +526,10 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
// @User: Standard
|
||||
GSCALAR(acro_yaw_p, "ACRO_YAW_P", ACRO_YAW_P),
|
||||
|
||||
#if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED
|
||||
// @Param: ACRO_BAL_ROLL
|
||||
// @DisplayName: Acro Balance Roll
|
||||
// @Description: rate at which roll angle returns to level in acro mode. A higher value causes the vehicle to return to level faster.
|
||||
// @Description: rate at which roll angle returns to level in acro and sport mode. A higher value causes the vehicle to return to level faster.
|
||||
// @Range: 0 3
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
|
@ -536,12 +537,14 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
|
||||
// @Param: ACRO_BAL_PITCH
|
||||
// @DisplayName: Acro Balance Pitch
|
||||
// @Description: rate at which pitch angle returns to level in acro mode. A higher value causes the vehicle to return to level faster.
|
||||
// @Description: rate at which pitch angle returns to level in acro and sport mode. A higher value causes the vehicle to return to level faster.
|
||||
// @Range: 0 3
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
GSCALAR(acro_balance_pitch, "ACRO_BAL_PITCH", ACRO_BALANCE_PITCH),
|
||||
#endif
|
||||
|
||||
#if MODE_ACRO_ENABLED == ENABLED
|
||||
// @Param: ACRO_TRAINER
|
||||
// @DisplayName: Acro Trainer
|
||||
// @Description: Type of trainer used in acro mode
|
||||
|
@ -556,6 +559,7 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
// @Range: -0.5 1.0
|
||||
// @User: Advanced
|
||||
GSCALAR(acro_rp_expo, "ACRO_RP_EXPO", ACRO_RP_EXPO_DEFAULT),
|
||||
#endif
|
||||
|
||||
// variables not in the g class which contain EEPROM saved variables
|
||||
|
||||
|
|
Loading…
Reference in New Issue