mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: re-order initialiser lines so -Werror=reorder will work
This commit is contained in:
parent
7147a2deeb
commit
5f5fb40753
|
@ -49,9 +49,9 @@ public:
|
|||
AP_MotorsHeli_RSC(SRV_Channel::Aux_servo_function_t aux_fn,
|
||||
uint8_t default_channel,
|
||||
uint8_t inst) :
|
||||
_instance(inst),
|
||||
_aux_fn(aux_fn),
|
||||
_default_channel(default_channel),
|
||||
_instance(inst)
|
||||
_default_channel(default_channel)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
};
|
||||
|
|
|
@ -89,8 +89,8 @@ const AP_Param::GroupInfo AP_MotorsHeli_Swash::var_info[] = {
|
|||
};
|
||||
|
||||
AP_MotorsHeli_Swash::AP_MotorsHeli_Swash(uint8_t mot_0, uint8_t mot_1, uint8_t mot_2, uint8_t mot_3, uint8_t instance) :
|
||||
_instance(instance),
|
||||
_motor_num{mot_0, mot_1, mot_2, mot_3}
|
||||
_motor_num{mot_0, mot_1, mot_2, mot_3},
|
||||
_instance(instance)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
|
|
@ -85,8 +85,8 @@ const AP_Param::GroupInfo Thrust_Linearization::var_info[] = {
|
|||
};
|
||||
|
||||
Thrust_Linearization::Thrust_Linearization(AP_Motors& _motors) :
|
||||
motors(_motors),
|
||||
lift_max(1.0)
|
||||
lift_max(1.0),
|
||||
motors(_motors)
|
||||
{
|
||||
// setup battery voltage filtering
|
||||
batt_voltage_filt.set_cutoff_frequency(AP_MOTORS_BATT_VOLT_FILT_HZ);
|
||||
|
|
Loading…
Reference in New Issue