Browse Source

APM_Control: cleanup some coverity warnings

mission-4.1.18
Andrew Tridgell 10 years ago
parent
commit
131b345ccc
  1. 4
      libraries/APM_Control/AP_AutoTune.cpp
  2. 6
      libraries/APM_Control/AP_AutoTune.h

4
libraries/APM_Control/AP_AutoTune.cpp

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

6
libraries/APM_Control/AP_AutoTune.h

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

Loading…
Cancel
Save