clang-tidy remove redundant init

This commit is contained in:
Daniel Agar 2017-04-23 22:08:11 -04:00
parent 8a681397bf
commit 5d626bd940
13 changed files with 8 additions and 39 deletions

View File

@ -88,21 +88,7 @@ AttPosEKF::AttPosEKF() :
statesAtVtasMeasTime{},
statesAtRngTime{},
statesAtFlowTime{},
correctedDelAng(),
correctedDelVel(),
summedDelAng(),
summedDelVel(),
prevDelAng(),
accNavMag(),
earthRateNED(),
angRate(),
lastGyroOffset(),
delAngTotal(),
Tbn(),
Tnb(),
accel(),
dVelIMU(),
dAngIMU(),
dtIMU(0.005f),
dtIMUfilt(0.005f),
dtVelPos(0.01f),
@ -119,7 +105,6 @@ AttPosEKF::AttPosEKF() :
rngMea(0.0f),
innovMag{},
varInnovMag{},
magData{},
innovVtas(0.0f),
innovRng(0.0f),
innovOptFlow{},
@ -132,7 +117,6 @@ AttPosEKF::AttPosEKF() :
lonRef(-M_PI_F),
hgtRef(0.0f),
refSet(false),
magBias(),
covSkipCount(0),
lastFixTime_ms(0),
globalTimeStamp_ms(0),
@ -176,7 +160,6 @@ AttPosEKF::AttPosEKF() :
auxFlowObsInnov{},
auxFlowObsInnovVar{},
fScaleFactorVar(0.0f),
Tnb_flow{},
R_LOS(0.0f),
auxFlowTestRatio{},
auxRngTestRatio(0.0f),

View File

@ -53,9 +53,7 @@ namespace control
Block::Block(SuperBlock *parent, const char *name) :
_name(name),
_parent(parent),
_dt(0),
_subscriptions(),
_params()
_dt(0)
{
if (getParent() != nullptr) {
getParent()->getChildren().add(this);

View File

@ -103,11 +103,7 @@ class __EXPORT SuperBlock :
public:
friend class Block;
// methods
SuperBlock(SuperBlock *parent, const char *name) :
Block(parent, name),
_children()
{
}
SuperBlock(SuperBlock *parent, const char *name) : Block(parent, name) {}
virtual ~SuperBlock() {};
virtual void setDt(float dt);
virtual void updateParams()

View File

@ -59,7 +59,6 @@ RunwayTakeoff::RunwayTakeoff() :
_init_yaw(0),
_climbout(false),
_throttle_ramp_time(2 * 1e6),
_start_wp(),
_runway_takeoff_enabled(this, "TKOFF"),
_heading_mode(this, "HDG"),
_nav_alt(this, "NAV_ALT"),

View File

@ -339,7 +339,6 @@ Ekf2::Ekf2():
_lp_roll_rate(250.0f, 30.0f),
_lp_pitch_rate(250.0f, 30.0f),
_lp_yaw_rate(250.0f, 20.0f),
_ekf(),
_params(_ekf.getParamHandle()),
_obs_dt_min_ms(this, "EKF2_MIN_OBS_DT", false, _params->sensor_interval_min_ms),
_mag_delay_ms(this, "EKF2_MAG_DELAY", false, _params->mag_delay_ms),

View File

@ -50,7 +50,7 @@
namespace land_detector
{
FixedwingLandDetector::FixedwingLandDetector() : LandDetector(),
FixedwingLandDetector::FixedwingLandDetector() :
_paramHandle(),
_params(),
_controlStateSub(-1),

View File

@ -49,7 +49,7 @@
namespace land_detector
{
MulticopterLandDetector::MulticopterLandDetector() : LandDetector(),
MulticopterLandDetector::MulticopterLandDetector() :
_paramHandle(),
_params(),
_vehicleLocalPositionSub(-1),

View File

@ -46,7 +46,7 @@
namespace land_detector
{
RoverLandDetector::RoverLandDetector() : LandDetector()
RoverLandDetector::RoverLandDetector()
{
}

View File

@ -46,7 +46,7 @@
namespace land_detector
{
VtolLandDetector::VtolLandDetector() : MulticopterLandDetector(),
VtolLandDetector::VtolLandDetector() :
_paramHandle(),
_params(),
_airspeedSub(-1),

View File

@ -148,10 +148,7 @@ BlockLocalPositionEstimator::BlockLocalPositionEstimator() :
// masks
_sensorTimeout(255),
_sensorFault(0),
_estimatorInitialized(0),
// kf matrices
_x(), _u(), _P(), _R_att(), _eul()
_estimatorInitialized(0)
{
// assign distance subs to array
_dist_subs[0] = &_sub_dist0;

View File

@ -248,7 +248,6 @@ Sensors *g_sensors = nullptr;
}
Sensors::Sensors(bool hil_enabled) :
_h_adc(),
_last_adc(0),
_task_should_exit(true),
@ -270,7 +269,6 @@ Sensors::Sensors(bool hil_enabled) :
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "sensors")),
_airspeed_validator(),
_rc_update(_parameters),
_voted_sensors_update(_parameters, hil_enabled)

View File

@ -312,7 +312,6 @@ GYROSIM::GYROSIM(const char *path_accel, const char *path_gyro, enum Rotation ro
VirtDevObj("GYROSIM", path_accel, ACCEL_BASE_DEVICE_PATH, 1e6 / 400),
_gyro(new GYROSIM_gyro(this, path_gyro)),
_product(GYROSIMES_REV_C4),
_call{},
_accel_reports(nullptr),
_accel_scale{},
_accel_range_scale(0.0f),

View File

@ -123,7 +123,7 @@ private:
MixerGroup mixer_group;
};
MixerTest::MixerTest() : UnitTest(),
MixerTest::MixerTest() :
mixer_group(mixer_callback, 0)
{
}