AP_MotorsMulticopter: initialise some members

This resolves some Covarity warnings at the cost of a small amount of flash
This commit is contained in:
Randy Mackay 2016-08-08 13:28:28 +09:00
parent 728e8f8f56
commit ad697243b3

View File

@ -144,12 +144,15 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
// Constructor // Constructor
AP_MotorsMulticopter::AP_MotorsMulticopter(uint16_t loop_rate, uint16_t speed_hz) : AP_MotorsMulticopter::AP_MotorsMulticopter(uint16_t loop_rate, uint16_t speed_hz) :
AP_Motors(loop_rate, speed_hz), AP_Motors(loop_rate, speed_hz),
_spool_mode(SHUT_DOWN),
_spin_up_ratio(0.0f),
_batt_voltage_resting(0.0f), _batt_voltage_resting(0.0f),
_batt_current_resting(0.0f), _batt_current_resting(0.0f),
_batt_resistance(0.0f), _batt_resistance(0.0f),
_batt_timer(0), _batt_timer(0),
_lift_max(1.0f), _lift_max(1.0f),
_throttle_limit(1.0f) _throttle_limit(1.0f),
_throttle_thrust_max(0.0f)
{ {
AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info);