From 5d626bd940ad938ea6de021b823321813567adcd Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sun, 23 Apr 2017 22:08:11 -0400 Subject: [PATCH] clang-tidy remove redundant init --- .../estimator_22states.cpp | 17 ----------------- src/lib/controllib/block/Block.cpp | 4 +--- src/lib/controllib/block/Block.hpp | 6 +----- src/lib/runway_takeoff/RunwayTakeoff.cpp | 1 - src/modules/ekf2/ekf2_main.cpp | 1 - .../land_detector/FixedwingLandDetector.cpp | 2 +- .../land_detector/MulticopterLandDetector.cpp | 2 +- src/modules/land_detector/RoverLandDetector.cpp | 2 +- src/modules/land_detector/VtolLandDetector.cpp | 2 +- .../BlockLocalPositionEstimator.cpp | 5 +---- src/modules/sensors/sensors.cpp | 2 -- src/platforms/posix/drivers/gyrosim/gyrosim.cpp | 1 - src/systemcmds/tests/test_mixer.cpp | 2 +- 13 files changed, 8 insertions(+), 39 deletions(-) diff --git a/src/examples/ekf_att_pos_estimator/estimator_22states.cpp b/src/examples/ekf_att_pos_estimator/estimator_22states.cpp index 86168bc361..f64a6ed451 100644 --- a/src/examples/ekf_att_pos_estimator/estimator_22states.cpp +++ b/src/examples/ekf_att_pos_estimator/estimator_22states.cpp @@ -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), diff --git a/src/lib/controllib/block/Block.cpp b/src/lib/controllib/block/Block.cpp index 460b254daa..16b415463e 100644 --- a/src/lib/controllib/block/Block.cpp +++ b/src/lib/controllib/block/Block.cpp @@ -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); diff --git a/src/lib/controllib/block/Block.hpp b/src/lib/controllib/block/Block.hpp index e1b42ffb5c..21d216f4fd 100644 --- a/src/lib/controllib/block/Block.hpp +++ b/src/lib/controllib/block/Block.hpp @@ -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() diff --git a/src/lib/runway_takeoff/RunwayTakeoff.cpp b/src/lib/runway_takeoff/RunwayTakeoff.cpp index c93089d3b9..178dc42ce8 100644 --- a/src/lib/runway_takeoff/RunwayTakeoff.cpp +++ b/src/lib/runway_takeoff/RunwayTakeoff.cpp @@ -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"), diff --git a/src/modules/ekf2/ekf2_main.cpp b/src/modules/ekf2/ekf2_main.cpp index 3619f68cf5..e100f71348 100644 --- a/src/modules/ekf2/ekf2_main.cpp +++ b/src/modules/ekf2/ekf2_main.cpp @@ -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), diff --git a/src/modules/land_detector/FixedwingLandDetector.cpp b/src/modules/land_detector/FixedwingLandDetector.cpp index b1812d6014..89d80a6f10 100644 --- a/src/modules/land_detector/FixedwingLandDetector.cpp +++ b/src/modules/land_detector/FixedwingLandDetector.cpp @@ -50,7 +50,7 @@ namespace land_detector { -FixedwingLandDetector::FixedwingLandDetector() : LandDetector(), +FixedwingLandDetector::FixedwingLandDetector() : _paramHandle(), _params(), _controlStateSub(-1), diff --git a/src/modules/land_detector/MulticopterLandDetector.cpp b/src/modules/land_detector/MulticopterLandDetector.cpp index a41356a877..88a33265a0 100644 --- a/src/modules/land_detector/MulticopterLandDetector.cpp +++ b/src/modules/land_detector/MulticopterLandDetector.cpp @@ -49,7 +49,7 @@ namespace land_detector { -MulticopterLandDetector::MulticopterLandDetector() : LandDetector(), +MulticopterLandDetector::MulticopterLandDetector() : _paramHandle(), _params(), _vehicleLocalPositionSub(-1), diff --git a/src/modules/land_detector/RoverLandDetector.cpp b/src/modules/land_detector/RoverLandDetector.cpp index c4067c2a9a..11b66c53fe 100644 --- a/src/modules/land_detector/RoverLandDetector.cpp +++ b/src/modules/land_detector/RoverLandDetector.cpp @@ -46,7 +46,7 @@ namespace land_detector { -RoverLandDetector::RoverLandDetector() : LandDetector() +RoverLandDetector::RoverLandDetector() { } diff --git a/src/modules/land_detector/VtolLandDetector.cpp b/src/modules/land_detector/VtolLandDetector.cpp index de6b983b57..6cb74e205f 100644 --- a/src/modules/land_detector/VtolLandDetector.cpp +++ b/src/modules/land_detector/VtolLandDetector.cpp @@ -46,7 +46,7 @@ namespace land_detector { -VtolLandDetector::VtolLandDetector() : MulticopterLandDetector(), +VtolLandDetector::VtolLandDetector() : _paramHandle(), _params(), _airspeedSub(-1), diff --git a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp index 8cb3383bf6..0ce8fa4739 100644 --- a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp +++ b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp @@ -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; diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index ed76ed4690..10434972fa 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -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) diff --git a/src/platforms/posix/drivers/gyrosim/gyrosim.cpp b/src/platforms/posix/drivers/gyrosim/gyrosim.cpp index 95af8936a2..0782efb23f 100644 --- a/src/platforms/posix/drivers/gyrosim/gyrosim.cpp +++ b/src/platforms/posix/drivers/gyrosim/gyrosim.cpp @@ -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), diff --git a/src/systemcmds/tests/test_mixer.cpp b/src/systemcmds/tests/test_mixer.cpp index 680409f42a..65368fe985 100644 --- a/src/systemcmds/tests/test_mixer.cpp +++ b/src/systemcmds/tests/test_mixer.cpp @@ -123,7 +123,7 @@ private: MixerGroup mixer_group; }; -MixerTest::MixerTest() : UnitTest(), +MixerTest::MixerTest() : mixer_group(mixer_callback, 0) { }