mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AC_AttitudeControl: CommandModel: use set_and_default method
This commit is contained in:
parent
3f84ba12c0
commit
c87d46e24d
@ -42,8 +42,8 @@ const AP_Param::GroupInfo AC_CommandModel::var_info[] = {
|
|||||||
AC_CommandModel::AC_CommandModel(float initial_rate, float initial_expo, float initial_tc)
|
AC_CommandModel::AC_CommandModel(float initial_rate, float initial_expo, float initial_tc)
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
rate = initial_rate;
|
rate.set_and_default(initial_rate);
|
||||||
expo = initial_expo;
|
expo.set_and_default(initial_expo);
|
||||||
rate_tc = initial_tc;
|
rate_tc.set_and_default(initial_tc);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user