mirror of https://github.com/ArduPilot/ardupilot
Copter: make rate time constants default to zero
This commit is contained in:
parent
2377d7a2c3
commit
e934fe89f2
|
@ -1189,14 +1189,14 @@ ParametersG2::ParametersG2(void)
|
|||
#endif
|
||||
|
||||
#if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED
|
||||
,command_model_acro_rp(ACRO_RP_RATE_DEFAULT, ACRO_RP_EXPO_DEFAULT, 0.05)
|
||||
,command_model_acro_rp(ACRO_RP_RATE_DEFAULT, ACRO_RP_EXPO_DEFAULT, 0.0f)
|
||||
#endif
|
||||
|
||||
#if MODE_ACRO_ENABLED == ENABLED || MODE_DRIFT_ENABLED == ENABLED
|
||||
,command_model_acro_y(ACRO_Y_RATE_DEFAULT, ACRO_Y_EXPO_DEFAULT, 0.05)
|
||||
,command_model_acro_y(ACRO_Y_RATE_DEFAULT, ACRO_Y_EXPO_DEFAULT, 0.0f)
|
||||
#endif
|
||||
|
||||
,command_model_pilot(PILOT_Y_RATE_DEFAULT, PILOT_Y_EXPO_DEFAULT, 0.05)
|
||||
,command_model_pilot(PILOT_Y_RATE_DEFAULT, PILOT_Y_EXPO_DEFAULT, 0.0f)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue