mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: adjust down default quadplane gains
make it better for a typical quadplane, the defaults were more suitable on smaller aircraft
This commit is contained in:
parent
08ae4f050c
commit
42f553626e
@ -478,6 +478,10 @@ static const struct AP_Param::defaults_table_struct defaults_table[] = {
|
||||
{ "Q_WP_SPEED", 500 },
|
||||
{ "Q_WP_ACCEL", 100 },
|
||||
{ "Q_P_JERK_XY", 2 },
|
||||
// lower rotational accel limits
|
||||
{ "Q_A_ACCEL_R_MAX", 40000 },
|
||||
{ "Q_A_ACCEL_P_MAX", 40000 },
|
||||
{ "Q_A_ACCEL_Y_MAX", 10000 },
|
||||
};
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user