APM_Control: cleanup some coverity warnings

This commit is contained in:
Andrew Tridgell 2015-06-20 13:30:32 +10:00
parent 2dbe372b2f
commit 131b345ccc
2 changed files with 6 additions and 4 deletions

View File

@ -70,10 +70,12 @@ extern const AP_HAL::HAL& hal;
AP_AutoTune::AP_AutoTune(ATGains &_gains, ATType _type, AP_AutoTune::AP_AutoTune(ATGains &_gains, ATType _type,
const AP_Vehicle::FixedWing &parms, const AP_Vehicle::FixedWing &parms,
DataFlash_Class &_dataflash) : DataFlash_Class &_dataflash) :
running(false),
current(_gains), current(_gains),
type(_type), type(_type),
aparm(parms), aparm(parms),
dataflash(_dataflash) dataflash(_dataflash),
saturated_surfaces(false)
{} {}
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #if CONFIG_HAL_BOARD == HAL_BOARD_SITL

View File

@ -77,17 +77,17 @@ private:
ATGains next_save; ATGains next_save;
// time when we last saved // time when we last saved
uint32_t last_save_ms; uint32_t last_save_ms = 0;
// the demanded/achieved state // the demanded/achieved state
enum ATState {DEMAND_UNSATURATED, enum ATState {DEMAND_UNSATURATED,
DEMAND_UNDER_POS, DEMAND_UNDER_POS,
DEMAND_OVER_POS, DEMAND_OVER_POS,
DEMAND_UNDER_NEG, DEMAND_UNDER_NEG,
DEMAND_OVER_NEG} state; DEMAND_OVER_NEG} state = DEMAND_UNSATURATED;
// when we entered the current state // when we entered the current state
uint32_t state_enter_ms; uint32_t state_enter_ms = 0;
void check_save(void); void check_save(void);
void check_state_exit(uint32_t state_time_ms); void check_state_exit(uint32_t state_time_ms);