AP_Motors: remove unneeded initialisations
This commit is contained in:
parent
9e6810933e
commit
937d8dac97
@ -56,10 +56,6 @@ public:
|
||||
AP_Motors(loop_rate, speed_hz)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
||||
// initialise flags
|
||||
_heliflags.landing_collective = 0;
|
||||
_heliflags.rotor_runup_complete = 0;
|
||||
};
|
||||
|
||||
// init
|
||||
|
@ -190,17 +190,11 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
|
||||
AP_MotorsMulticopter::AP_MotorsMulticopter(uint16_t loop_rate, uint16_t speed_hz) :
|
||||
AP_Motors(loop_rate, speed_hz),
|
||||
_spool_mode(SHUT_DOWN),
|
||||
_spin_up_ratio(0.0f),
|
||||
_lift_max(1.0f),
|
||||
_throttle_limit(1.0f),
|
||||
_throttle_thrust_max(0.0f),
|
||||
_disarm_safety_timer(0)
|
||||
_throttle_limit(1.0f)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
||||
// disable all motors by default
|
||||
memset(motor_enabled, false, sizeof(motor_enabled));
|
||||
|
||||
// setup battery voltage filtering
|
||||
_batt_voltage_filt.set_cutoff_frequency(AP_MOTORS_BATT_VOLT_FILT_HZ);
|
||||
_batt_voltage_filt.reset(1.0f);
|
||||
|
@ -33,22 +33,11 @@ AP_Motors *AP_Motors::_instance;
|
||||
AP_Motors::AP_Motors(uint16_t loop_rate, uint16_t speed_hz) :
|
||||
_loop_rate(loop_rate),
|
||||
_speed_hz(speed_hz),
|
||||
_roll_in(0.0f),
|
||||
_pitch_in(0.0f),
|
||||
_yaw_in(0.0f),
|
||||
_throttle_in(0.0f),
|
||||
_throttle_avg_max(0.0f),
|
||||
_throttle_filter(),
|
||||
_spool_desired(DESIRED_SHUT_DOWN),
|
||||
_air_density_ratio(1.0f),
|
||||
_motor_fast_mask(0)
|
||||
_air_density_ratio(1.0f)
|
||||
{
|
||||
_instance = this;
|
||||
|
||||
// init other flags
|
||||
_flags.armed = false;
|
||||
_flags.interlock = false;
|
||||
_flags.initialised_ok = false;
|
||||
|
||||
// setup throttle filtering
|
||||
_throttle_filter.set_cutoff_frequency(0.0f);
|
||||
|
Loading…
Reference in New Issue
Block a user