diff --git a/demos/hello_wolf/capture_range_bearing.h b/demos/hello_wolf/capture_range_bearing.h index 8bc32a93d452629b5c69358c5d751c070eeba1a6..10fb8fa05f14fc4801effce4fb734c90a9ea2e90 100644 --- a/demos/hello_wolf/capture_range_bearing.h +++ b/demos/hello_wolf/capture_range_bearing.h @@ -21,7 +21,7 @@ class CaptureRangeBearing : public CaptureBase { public: CaptureRangeBearing(const TimeStamp& _ts, const SensorBasePtr& _scanner, const Eigen::VectorXi& _ids, const Eigen::VectorXd& _ranges, const Eigen::VectorXd& _bearings); - virtual ~CaptureRangeBearing(); + ~CaptureRangeBearing() override; const VectorXi& getIds () const; const int& getId (int _i) const; diff --git a/demos/hello_wolf/factor_range_bearing.h b/demos/hello_wolf/factor_range_bearing.h index 226a6335e7966a0d3bdd7042c017913bc64b419b..978f88846d5dee608a47a01c101676a0bfd23037 100644 --- a/demos/hello_wolf/factor_range_bearing.h +++ b/demos/hello_wolf/factor_range_bearing.h @@ -45,12 +45,12 @@ class FactorRangeBearing : public FactorAutodiff<FactorRangeBearing, 2, 2, 1, 2, // } - virtual ~FactorRangeBearing() + ~FactorRangeBearing() override { // } - virtual std::string getTopology() const override + std::string getTopology() const override { return "LMK"; } diff --git a/demos/hello_wolf/feature_range_bearing.h b/demos/hello_wolf/feature_range_bearing.h index 8571a8fb933976c740440c9d4d9ba8a2fb3d8f20..b924d29eea0a22a80267ace90718f9a66f54dac1 100644 --- a/demos/hello_wolf/feature_range_bearing.h +++ b/demos/hello_wolf/feature_range_bearing.h @@ -19,7 +19,7 @@ class FeatureRangeBearing : public FeatureBase { public: FeatureRangeBearing(const Eigen::VectorXd& _measurement, const Eigen::MatrixXd& _meas_covariance); - virtual ~FeatureRangeBearing(); + ~FeatureRangeBearing() override; }; } // namespace wolf diff --git a/demos/hello_wolf/landmark_point_2d.h b/demos/hello_wolf/landmark_point_2d.h index 0ec660c9e70944a8de9dd152649dc78d8a85b86b..79287af069fb5b5da0ef7186333b90fc18664bbb 100644 --- a/demos/hello_wolf/landmark_point_2d.h +++ b/demos/hello_wolf/landmark_point_2d.h @@ -19,7 +19,7 @@ class LandmarkPoint2d : public LandmarkBase { public: LandmarkPoint2d(int _id, const Eigen::Vector2d& _xy); - virtual ~LandmarkPoint2d(); + ~LandmarkPoint2d() override; }; } /* namespace wolf */ diff --git a/demos/hello_wolf/processor_range_bearing.h b/demos/hello_wolf/processor_range_bearing.h index 1203b217e4f07c3e02a287f63b0bace4ba46ede2..bdcefb3a7141627523a6f2111307fc776abbadbb 100644 --- a/demos/hello_wolf/processor_range_bearing.h +++ b/demos/hello_wolf/processor_range_bearing.h @@ -46,31 +46,31 @@ class ProcessorRangeBearing : public ProcessorBase typedef Eigen::Transform<double, 2, Eigen::Isometry> Trf; ProcessorRangeBearing(ParamsProcessorBasePtr _params); - virtual ~ProcessorRangeBearing() {/* empty */} - virtual void configure(SensorBasePtr _sensor) override; + ~ProcessorRangeBearing() override {/* empty */} + void configure(SensorBasePtr _sensor) override; // Factory method for high level API WOLF_PROCESSOR_CREATE(ProcessorRangeBearing, ParamsProcessorRangeBearing); protected: // Implementation of pure virtuals from ProcessorBase - virtual void processCapture (CaptureBasePtr _capture) override; - virtual void processKeyFrame (FrameBasePtr _keyframe_ptr, const double& _time_tol_other) override {}; - virtual bool triggerInCapture (CaptureBasePtr) const override { return true;}; - virtual bool triggerInKeyFrame (FrameBasePtr _keyframe_ptr, const double& _time_tol_other) const override {return false;} - virtual bool voteForKeyFrame () const override {return false;} + void processCapture (CaptureBasePtr _capture) override; + void processKeyFrame (FrameBasePtr _keyframe_ptr, const double& _time_tol_other) override {}; + bool triggerInCapture (CaptureBasePtr) const override { return true;}; + bool triggerInKeyFrame (FrameBasePtr _keyframe_ptr, const double& _time_tol_other) const override {return false;} + bool voteForKeyFrame () const override {return false;} /** \brief store key frame * * Returns true if the key frame should be stored */ - virtual bool storeKeyFrame(FrameBasePtr) override; + bool storeKeyFrame(FrameBasePtr) override; /** \brief store capture * * Returns true if the capture should be stored */ - virtual bool storeCapture(CaptureBasePtr) override; + bool storeCapture(CaptureBasePtr) override; private: // control variables diff --git a/demos/hello_wolf/sensor_range_bearing.h b/demos/hello_wolf/sensor_range_bearing.h index 491efff4f533edc993051482de7d0e84562a790a..59c217fe0f3f9f5f70973dca8a2ef4b060a6696a 100644 --- a/demos/hello_wolf/sensor_range_bearing.h +++ b/demos/hello_wolf/sensor_range_bearing.h @@ -45,7 +45,7 @@ class SensorRangeBearing : public SensorBase SensorRangeBearing(const Eigen::VectorXd& _extrinsics, const Eigen::Vector2d& _noise_std); SensorRangeBearing(const Eigen::VectorXd& _extrinsics, const ParamsSensorRangeBearingPtr _intr); WOLF_SENSOR_CREATE(SensorRangeBearing, ParamsSensorRangeBearing, 3); - virtual ~SensorRangeBearing(); + ~SensorRangeBearing() override; }; diff --git a/include/core/capture/capture_base.h b/include/core/capture/capture_base.h index d4e215e47cd576b48797c4e9f028be5a5a64edf1..c10374ae82ae1a8f495e6adc3bea5b7f167b548b 100644 --- a/include/core/capture/capture_base.h +++ b/include/core/capture/capture_base.h @@ -35,7 +35,7 @@ class CaptureBase : public NodeBase, public HasStateBlocks, public std::enable_s protected: unsigned int capture_id_; TimeStamp time_stamp_; ///< Time stamp - virtual void setProblem(ProblemPtr _problem) final; + void setProblem(ProblemPtr _problem) override final; public: @@ -46,7 +46,7 @@ class CaptureBase : public NodeBase, public HasStateBlocks, public std::enable_s StateBlockPtr _o_ptr = nullptr, StateBlockPtr _intr_ptr = nullptr); - virtual ~CaptureBase(); + ~CaptureBase() override; virtual void remove(bool viral_remove_empty_parent=false); // Type @@ -89,8 +89,8 @@ class CaptureBase : public NodeBase, public HasStateBlocks, public std::enable_s StateBlockPtr getSensorO() const; StateBlockPtr getSensorIntrinsic() const; - virtual void fix() override; - virtual void unfix() override; + void fix() override; + void unfix() override; void move(FrameBasePtr); void link(FrameBasePtr); diff --git a/include/core/capture/capture_diff_drive.h b/include/core/capture/capture_diff_drive.h index 52e865da7d6d3e441643480d9a5e6acc0014aa89..e9797427f3550289906e159c40fefe681d2e55ad 100644 --- a/include/core/capture/capture_diff_drive.h +++ b/include/core/capture/capture_diff_drive.h @@ -37,7 +37,7 @@ public: StateBlockPtr _o_ptr = nullptr, StateBlockPtr _intr_ptr = nullptr); - virtual ~CaptureDiffDrive() = default; + ~CaptureDiffDrive() override = default; }; } // namespace wolf diff --git a/include/core/capture/capture_motion.h b/include/core/capture/capture_motion.h index fca231eeb7142aa456171c95438d0b322927a88d..c0d86ee1089740ecf03b3896f9264cdc2de5db88 100644 --- a/include/core/capture/capture_motion.h +++ b/include/core/capture/capture_motion.h @@ -62,10 +62,10 @@ class CaptureMotion : public CaptureBase StateBlockPtr _o_ptr = nullptr, StateBlockPtr _intr_ptr = nullptr); - virtual ~CaptureMotion(); + ~CaptureMotion() override; // Type - virtual bool isMotion() const override { return true; } + bool isMotion() const override { return true; } // Data const Eigen::VectorXd& getData() const; @@ -96,7 +96,7 @@ class CaptureMotion : public CaptureBase bool containsTimeStamp(const TimeStamp& _ts, double _time_tolerance); - virtual void printHeader(int depth, // + void printHeader(int depth, // bool constr_by, // bool metric, // bool state_blocks, diff --git a/include/core/capture/capture_odom_2d.h b/include/core/capture/capture_odom_2d.h index 8856c363a7f576413a3428fa7b206ab6bd17f824..e0a81bf2d47cad9b8d564f11eb011574daae76d4 100644 --- a/include/core/capture/capture_odom_2d.h +++ b/include/core/capture/capture_odom_2d.h @@ -31,7 +31,7 @@ class CaptureOdom2d : public CaptureMotion const Eigen::MatrixXd& _data_cov, CaptureBasePtr _capture_origin_ptr = nullptr); - virtual ~CaptureOdom2d(); + ~CaptureOdom2d() override; }; diff --git a/include/core/capture/capture_odom_3d.h b/include/core/capture/capture_odom_3d.h index b4a293f8c4059b9346a334c31e017a967267a902..054c4f935ca63f73fd6fbbb87bab70a10655e5c3 100644 --- a/include/core/capture/capture_odom_3d.h +++ b/include/core/capture/capture_odom_3d.h @@ -31,7 +31,7 @@ class CaptureOdom3d : public CaptureMotion const Eigen::MatrixXd& _data_cov, CaptureBasePtr _capture_origin_ptr = nullptr); - virtual ~CaptureOdom3d(); + ~CaptureOdom3d() override; }; diff --git a/include/core/capture/capture_pose.h b/include/core/capture/capture_pose.h index 56ce0ea48c5aadd9d3b189353bae75b83088d792..79298fe4d63b03b3c0ad830f4265c106ca30ae74 100644 --- a/include/core/capture/capture_pose.h +++ b/include/core/capture/capture_pose.h @@ -25,7 +25,7 @@ class CapturePose : public CaptureBase CapturePose(const TimeStamp& _ts, SensorBasePtr _sensor_ptr, const Eigen::VectorXd& _data, const Eigen::MatrixXd& _data_covariance); - virtual ~CapturePose(); + ~CapturePose() override; virtual void emplaceFeatureAndFactor(); diff --git a/include/core/capture/capture_void.h b/include/core/capture/capture_void.h index c0bd4803d42cc61116265cc9625b83f52e347efb..0ac7b3b2fc9ed44c4ac430fd9f70387435f05227 100644 --- a/include/core/capture/capture_void.h +++ b/include/core/capture/capture_void.h @@ -14,7 +14,7 @@ class CaptureVoid : public CaptureBase { public: CaptureVoid(const TimeStamp& _ts, SensorBasePtr _sensor_ptr); - virtual ~CaptureVoid(); + ~CaptureVoid() override; }; diff --git a/include/core/ceres_wrapper/ceres_manager.h b/include/core/ceres_wrapper/ceres_manager.h index 0841f7421ef37f039b2fa77449ffafefd52b7118..dd88e5db6bf3b7ac38a925a64ba66c089dbb09ec 100644 --- a/include/core/ceres_wrapper/ceres_manager.h +++ b/include/core/ceres_wrapper/ceres_manager.h @@ -30,7 +30,7 @@ struct CeresParams : public SolverParams // } - virtual ~CeresParams() = default; + ~CeresParams() override = default; }; /** \brief Ceres manager for WOLF * @@ -56,7 +56,7 @@ class CeresManager : public SolverManager const ceres::Solver::Options& _ceres_options = ceres::Solver::Options()); - ~CeresManager(); + ~CeresManager() override; static SolverManagerPtr create(const ProblemPtr& _wolf_problem, const ParamsServer& _server); @@ -64,18 +64,18 @@ class CeresManager : public SolverManager std::unique_ptr<ceres::Problem>& getCeresProblem(); - virtual void computeCovariances(CovarianceBlocksToBeComputed _blocks + void computeCovariances(CovarianceBlocksToBeComputed _blocks = CovarianceBlocksToBeComputed::ROBOT_LANDMARKS) override; - virtual void computeCovariances(const std::vector<StateBlockPtr>& st_list) override; + void computeCovariances(const std::vector<StateBlockPtr>& st_list) override; - virtual bool hasConverged() override; + bool hasConverged() override; - virtual SizeStd iterations() override; + SizeStd iterations() override; - virtual double initialCost() override; + double initialCost() override; - virtual double finalCost() override; + double finalCost() override; ceres::Solver::Options& getSolverOptions(); @@ -84,27 +84,27 @@ class CeresManager : public SolverManager protected: - virtual bool checkDerived(std::string prefix="") const override; + bool checkDerived(std::string prefix="") const override; - virtual std::string solveDerived(const ReportVerbosity report_level) override; + std::string solveDerived(const ReportVerbosity report_level) override; - virtual void addFactorDerived(const FactorBasePtr& fac_ptr) override; + void addFactorDerived(const FactorBasePtr& fac_ptr) override; - virtual void removeFactorDerived(const FactorBasePtr& fac_ptr) override; + void removeFactorDerived(const FactorBasePtr& fac_ptr) override; - virtual void addStateBlockDerived(const StateBlockPtr& state_ptr) override; + void addStateBlockDerived(const StateBlockPtr& state_ptr) override; - virtual void removeStateBlockDerived(const StateBlockPtr& state_ptr) override; + void removeStateBlockDerived(const StateBlockPtr& state_ptr) override; - virtual void updateStateBlockStatusDerived(const StateBlockPtr& state_ptr) override; + void updateStateBlockStatusDerived(const StateBlockPtr& state_ptr) override; - virtual void updateStateBlockLocalParametrizationDerived(const StateBlockPtr& state_ptr) override; + void updateStateBlockLocalParametrizationDerived(const StateBlockPtr& state_ptr) override; ceres::CostFunctionPtr createCostFunction(const FactorBasePtr& _fac_ptr); - virtual bool isFactorRegisteredDerived(const FactorBasePtr& fac_ptr) const override; + bool isFactorRegisteredDerived(const FactorBasePtr& fac_ptr) const override; - virtual bool isStateBlockRegisteredDerived(const StateBlockPtr& state_ptr) override; + bool isStateBlockRegisteredDerived(const StateBlockPtr& state_ptr) override; }; inline ceres::Solver::Summary CeresManager::getSummary() diff --git a/include/core/ceres_wrapper/cost_function_wrapper.h b/include/core/ceres_wrapper/cost_function_wrapper.h index 69cbf125bc44f89066377a0754c2af6ada6e36df..c9972fe780e76c243ed1a298f658d6e702fe8d1e 100644 --- a/include/core/ceres_wrapper/cost_function_wrapper.h +++ b/include/core/ceres_wrapper/cost_function_wrapper.h @@ -25,9 +25,9 @@ class CostFunctionWrapper : public ceres::CostFunction CostFunctionWrapper(FactorBasePtr _factor_ptr); - virtual ~CostFunctionWrapper(); + ~CostFunctionWrapper() override; - virtual bool Evaluate(const double* const * parameters, double* residuals, double** jacobians) const; + bool Evaluate(const double* const * parameters, double* residuals, double** jacobians) const override; FactorBasePtr getFactor() const; }; diff --git a/include/core/ceres_wrapper/local_parametrization_wrapper.h b/include/core/ceres_wrapper/local_parametrization_wrapper.h index cb02cb8f01f4256d1223d9d2bf3e686a2ef5b76f..fcffbbf80ed9b09717dd830fe250facd70bf9985 100644 --- a/include/core/ceres_wrapper/local_parametrization_wrapper.h +++ b/include/core/ceres_wrapper/local_parametrization_wrapper.h @@ -21,15 +21,15 @@ class LocalParametrizationWrapper : public ceres::LocalParameterization LocalParametrizationWrapper(LocalParametrizationBasePtr _local_parametrization_ptr); - virtual ~LocalParametrizationWrapper() = default; + ~LocalParametrizationWrapper() override = default; - virtual bool Plus(const double* x_raw, const double* delta_raw, double* x_plus_delta_raw) const; + bool Plus(const double* x_raw, const double* delta_raw, double* x_plus_delta_raw) const override; - virtual bool ComputeJacobian(const double* x, double* jacobian) const; + bool ComputeJacobian(const double* x, double* jacobian) const override; - virtual int GlobalSize() const; + int GlobalSize() const override; - virtual int LocalSize() const; + int LocalSize() const override; LocalParametrizationBasePtr getLocalParametrization() const; }; diff --git a/include/core/factor/factor_analytic.h b/include/core/factor/factor_analytic.h index 34fd699a7b1461f9ab147c9d5d9f6ef2496b2f97..c05b1a2e1345c137129b2d00849d95389fbf6174 100644 --- a/include/core/factor/factor_analytic.h +++ b/include/core/factor/factor_analytic.h @@ -38,21 +38,21 @@ class FactorAnalytic: public FactorBase StateBlockPtr _state8Ptr = nullptr, StateBlockPtr _state9Ptr = nullptr ); - virtual ~FactorAnalytic() = default; + ~FactorAnalytic() override = default; /** \brief Returns a vector of pointers to the states * * Returns a vector of pointers to the state in which this factor depends * **/ - virtual std::vector<StateBlockPtr> getStateBlockPtrVector() const override; + std::vector<StateBlockPtr> getStateBlockPtrVector() const override; /** \brief Returns a vector of sizes of the state blocks * * Returns a vector of sizes of the state blocks * **/ - virtual std::vector<unsigned int> getStateSizes() const override; + std::vector<unsigned int> getStateSizes() const override; /** \brief Returns the factor residual size * @@ -63,7 +63,7 @@ class FactorAnalytic: public FactorBase /** \brief Evaluate the factor given the input parameters and returning the residuals and jacobians **/ - virtual bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const override + bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const override { // load parameters evaluation value std::vector<Eigen::Map<const Eigen::VectorXd>> state_blocks_map_; @@ -97,7 +97,7 @@ class FactorAnalytic: public FactorBase /** Returns the residual vector and a vector of Jacobian matrix corresponding to each state block evaluated in the point provided in _states_ptr **/ - virtual void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const override + void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const override { assert(_states_ptr.size() == state_block_sizes_vector_.size()); @@ -152,7 +152,7 @@ class FactorAnalytic: public FactorBase * Returns the jacobians computation method * **/ - virtual JacobianMethod getJacobianMethod() const override; + JacobianMethod getJacobianMethod() const override; private: void resizeVectors(); diff --git a/include/core/factor/factor_autodiff.h b/include/core/factor/factor_autodiff.h index dce0203c894704953ff3001732f418b2636343a3..8b3ab6f9c8cc10dc45b53f02c45c59e1844eba13 100644 --- a/include/core/factor/factor_autodiff.h +++ b/include/core/factor/factor_autodiff.h @@ -129,11 +129,11 @@ class FactorAutodiff : public FactorBase jets_11_[i] = WolfJet(0, last_jet_idx++); } - virtual ~FactorAutodiff() + ~FactorAutodiff() override { } - virtual JacobianMethod getJacobianMethod() const + JacobianMethod getJacobianMethod() const override { return JAC_AUTO; } @@ -143,7 +143,7 @@ class FactorAutodiff : public FactorBase * Returns the residual and jacobians given the state values * **/ - virtual bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const + bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const override { // only residuals if (jacobians == nullptr) @@ -235,7 +235,7 @@ class FactorAutodiff : public FactorBase /** \brief Returns a vector of Jacobian matrix corresponding to each state block evaluated in the point provided in _states_ptr * **/ - virtual void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const + void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const override { assert(residual_.size() == RES); jacobians_.clear(); @@ -289,7 +289,7 @@ class FactorAutodiff : public FactorBase * Returns a vector of pointers to the state in which this factor depends * **/ - virtual std::vector<StateBlockPtr> getStateBlockPtrVector() const + std::vector<StateBlockPtr> getStateBlockPtrVector() const override { return state_ptrs_; } @@ -297,7 +297,7 @@ class FactorAutodiff : public FactorBase /** \brief Returns a vector of the states sizes * **/ - virtual std::vector<unsigned int> getStateSizes() const + std::vector<unsigned int> getStateSizes() const override { return state_block_sizes_; } @@ -307,7 +307,7 @@ class FactorAutodiff : public FactorBase * Returns the residual size * **/ - virtual unsigned int getSize() const + unsigned int getSize() const override { return RES; } @@ -424,16 +424,16 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,B5,B6,B7,B8,B9,B10,0> : public Fact state_ptrs_.resize(n_blocks); } - virtual ~FactorAutodiff() + ~FactorAutodiff() override { } - virtual JacobianMethod getJacobianMethod() const + JacobianMethod getJacobianMethod() const override { return JAC_AUTO; } - virtual bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const + bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const override { // only residuals if (jacobians == nullptr) @@ -515,7 +515,7 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,B5,B6,B7,B8,B9,B10,0> : public Fact jets_10_[i].a = parameters[10][i]; } - virtual void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const + void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const override { assert(residual_.size() == RES); jacobians_.clear(); @@ -563,17 +563,17 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,B5,B6,B7,B8,B9,B10,0> : public Fact // std::cout << jacobians_[i] << std::endl << std::endl; } - virtual std::vector<StateBlockPtr> getStateBlockPtrVector() const + std::vector<StateBlockPtr> getStateBlockPtrVector() const override { return state_ptrs_; } - virtual std::vector<unsigned int> getStateSizes() const + std::vector<unsigned int> getStateSizes() const override { return state_block_sizes_; } - virtual unsigned int getSize() const + unsigned int getSize() const override { return RES; } @@ -684,16 +684,16 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,B5,B6,B7,B8,B9,0,0> : public Factor state_ptrs_.resize(n_blocks); } - virtual ~FactorAutodiff() + ~FactorAutodiff() override { } - virtual JacobianMethod getJacobianMethod() const + JacobianMethod getJacobianMethod() const override { return JAC_AUTO; } - virtual bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const + bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const override { // only residuals if (jacobians == nullptr) @@ -771,7 +771,7 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,B5,B6,B7,B8,B9,0,0> : public Factor jets_9_[i].a = parameters[9][i]; } - virtual void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const + void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const override { assert(residual_.size() == RES); jacobians_.clear(); @@ -818,17 +818,17 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,B5,B6,B7,B8,B9,0,0> : public Factor // std::cout << jacobians_[i] << std::endl << std::endl; } - virtual std::vector<StateBlockPtr> getStateBlockPtrVector() const + std::vector<StateBlockPtr> getStateBlockPtrVector() const override { return state_ptrs_; } - virtual std::vector<unsigned int> getStateSizes() const + std::vector<unsigned int> getStateSizes() const override { return state_block_sizes_; } - virtual unsigned int getSize() const + unsigned int getSize() const override { return RES; } @@ -934,16 +934,16 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,B5,B6,B7,B8,0,0,0> : public FactorB state_ptrs_.resize(n_blocks); } - virtual ~FactorAutodiff() + ~FactorAutodiff() override { } - virtual JacobianMethod getJacobianMethod() const + JacobianMethod getJacobianMethod() const override { return JAC_AUTO; } - virtual bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const + bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const override { // only residuals if (jacobians == nullptr) @@ -1017,7 +1017,7 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,B5,B6,B7,B8,0,0,0> : public FactorB jets_8_[i].a = parameters[8][i]; } - virtual void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const + void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const override { assert(residual_.size() == RES); jacobians_.clear(); @@ -1063,17 +1063,17 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,B5,B6,B7,B8,0,0,0> : public FactorB // std::cout << jacobians_[i] << std::endl << std::endl; } - virtual std::vector<StateBlockPtr> getStateBlockPtrVector() const + std::vector<StateBlockPtr> getStateBlockPtrVector() const override { return state_ptrs_; } - virtual std::vector<unsigned int> getStateSizes() const + std::vector<unsigned int> getStateSizes() const override { return state_block_sizes_; } - virtual unsigned int getSize() const + unsigned int getSize() const override { return RES; } @@ -1174,16 +1174,16 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,B5,B6,B7,0,0,0,0> : public FactorBa state_ptrs_.resize(n_blocks); } - virtual ~FactorAutodiff() + ~FactorAutodiff() override { } - virtual JacobianMethod getJacobianMethod() const + JacobianMethod getJacobianMethod() const override { return JAC_AUTO; } - virtual bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const + bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const override { // only residuals if (jacobians == nullptr) @@ -1253,7 +1253,7 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,B5,B6,B7,0,0,0,0> : public FactorBa jets_7_[i].a = parameters[7][i]; } - virtual void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const + void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const override { assert(residual_.size() == RES); jacobians_.clear(); @@ -1298,17 +1298,17 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,B5,B6,B7,0,0,0,0> : public FactorBa // std::cout << jacobians_[i] << std::endl << std::endl; } - virtual std::vector<StateBlockPtr> getStateBlockPtrVector() const + std::vector<StateBlockPtr> getStateBlockPtrVector() const override { return state_ptrs_; } - virtual std::vector<unsigned int> getStateSizes() const + std::vector<unsigned int> getStateSizes() const override { return state_block_sizes_; } - virtual unsigned int getSize() const + unsigned int getSize() const override { return RES; } @@ -1404,16 +1404,16 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,B5,B6,0,0,0,0,0> : public FactorBas state_ptrs_.resize(n_blocks); } - virtual ~FactorAutodiff() + ~FactorAutodiff() override { } - virtual JacobianMethod getJacobianMethod() const + JacobianMethod getJacobianMethod() const override { return JAC_AUTO; } - virtual bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const + bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const override { // only residuals if (jacobians == nullptr) @@ -1479,7 +1479,7 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,B5,B6,0,0,0,0,0> : public FactorBas jets_6_[i].a = parameters[6][i]; } - virtual void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const + void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const override { assert(residual_.size() == RES); jacobians_.clear(); @@ -1523,17 +1523,17 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,B5,B6,0,0,0,0,0> : public FactorBas // std::cout << jacobians_[i] << std::endl << std::endl; } - virtual std::vector<StateBlockPtr> getStateBlockPtrVector() const + std::vector<StateBlockPtr> getStateBlockPtrVector() const override { return state_ptrs_; } - virtual std::vector<unsigned int> getStateSizes() const + std::vector<unsigned int> getStateSizes() const override { return state_block_sizes_; } - virtual unsigned int getSize() const + unsigned int getSize() const override { return RES; } @@ -1624,16 +1624,16 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,B5,0,0,0,0,0,0> : public FactorBase state_ptrs_.resize(n_blocks); } - virtual ~FactorAutodiff() + ~FactorAutodiff() override { } - virtual JacobianMethod getJacobianMethod() const + JacobianMethod getJacobianMethod() const override { return JAC_AUTO; } - virtual bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const + bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const override { // only residuals if (jacobians == nullptr) @@ -1695,7 +1695,7 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,B5,0,0,0,0,0,0> : public FactorBase jets_5_[i].a = parameters[5][i]; } - virtual void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const + void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const override { assert(residual_.size() == RES); jacobians_.clear(); @@ -1734,17 +1734,17 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,B5,0,0,0,0,0,0> : public FactorBase } } - virtual std::vector<StateBlockPtr> getStateBlockPtrVector() const + std::vector<StateBlockPtr> getStateBlockPtrVector() const override { return state_ptrs_; } - virtual std::vector<unsigned int> getStateSizes() const + std::vector<unsigned int> getStateSizes() const override { return state_block_sizes_; } - virtual unsigned int getSize() const + unsigned int getSize() const override { return RES; } @@ -1829,16 +1829,16 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,0,0,0,0,0,0,0> : public FactorBase state_ptrs_.resize(n_blocks); } - virtual ~FactorAutodiff() + ~FactorAutodiff() override { } - virtual JacobianMethod getJacobianMethod() const + JacobianMethod getJacobianMethod() const override { return JAC_AUTO; } - virtual bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const + bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const override { // only residuals if (jacobians == nullptr) @@ -1896,7 +1896,7 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,0,0,0,0,0,0,0> : public FactorBase jets_4_[i].a = parameters[4][i]; } - virtual void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const + void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const override { assert(residual_.size() == RES); jacobians_.clear(); @@ -1934,17 +1934,17 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,B4,0,0,0,0,0,0,0> : public FactorBase } } - virtual std::vector<StateBlockPtr> getStateBlockPtrVector() const + std::vector<StateBlockPtr> getStateBlockPtrVector() const override { return state_ptrs_; } - virtual std::vector<unsigned int> getStateSizes() const + std::vector<unsigned int> getStateSizes() const override { return state_block_sizes_; } - virtual unsigned int getSize() const + unsigned int getSize() const override { return RES; } @@ -2024,16 +2024,16 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,0,0,0,0,0,0,0,0> : public FactorBase state_ptrs_.resize(n_blocks); } - virtual ~FactorAutodiff() + ~FactorAutodiff() override { } - virtual JacobianMethod getJacobianMethod() const + JacobianMethod getJacobianMethod() const override { return JAC_AUTO; } - virtual bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const + bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const override { // only residuals if (jacobians == nullptr) @@ -2087,7 +2087,7 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,0,0,0,0,0,0,0,0> : public FactorBase jets_3_[i].a = parameters[3][i]; } - virtual void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const + void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const override { assert(residual_.size() == RES); jacobians_.clear(); @@ -2128,17 +2128,17 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,B3,0,0,0,0,0,0,0,0> : public FactorBase // std::cout << jacobians_[i] << std::endl << std::endl; } - virtual std::vector<StateBlockPtr> getStateBlockPtrVector() const + std::vector<StateBlockPtr> getStateBlockPtrVector() const override { return state_ptrs_; } - virtual std::vector<unsigned int> getStateSizes() const + std::vector<unsigned int> getStateSizes() const override { return state_block_sizes_; } - virtual unsigned int getSize() const + unsigned int getSize() const override { return RES; } @@ -2213,16 +2213,16 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,0,0,0,0,0,0,0,0,0> : public FactorBase state_ptrs_.resize(n_blocks); } - virtual ~FactorAutodiff() + ~FactorAutodiff() override { } - virtual JacobianMethod getJacobianMethod() const + JacobianMethod getJacobianMethod() const override { return JAC_AUTO; } - virtual bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const + bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const override { // only residuals if (jacobians == nullptr) @@ -2272,7 +2272,7 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,0,0,0,0,0,0,0,0,0> : public FactorBase jets_2_[i].a = parameters[2][i]; } - virtual void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const + void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const override { assert(residual_.size() == RES); jacobians_.clear(); @@ -2312,17 +2312,17 @@ class FactorAutodiff<FacT,RES,B0,B1,B2,0,0,0,0,0,0,0,0,0> : public FactorBase // std::cout << jacobians_[i] << std::endl << std::endl; } - virtual std::vector<StateBlockPtr> getStateBlockPtrVector() const + std::vector<StateBlockPtr> getStateBlockPtrVector() const override { return state_ptrs_; } - virtual std::vector<unsigned int> getStateSizes() const + std::vector<unsigned int> getStateSizes() const override { return state_block_sizes_; } - virtual unsigned int getSize() const + unsigned int getSize() const override { return RES; } @@ -2392,16 +2392,16 @@ class FactorAutodiff<FacT,RES,B0,B1,0,0,0,0,0,0,0,0,0,0> : public FactorBase state_ptrs_.resize(n_blocks); } - virtual ~FactorAutodiff() + ~FactorAutodiff() override { } - virtual JacobianMethod getJacobianMethod() const + JacobianMethod getJacobianMethod() const override { return JAC_AUTO; } - virtual bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const + bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const override { // only residuals if (jacobians == nullptr) @@ -2447,7 +2447,7 @@ class FactorAutodiff<FacT,RES,B0,B1,0,0,0,0,0,0,0,0,0,0> : public FactorBase jets_1_[i].a = parameters[1][i]; } - virtual void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const + void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const override { assert(residual_.size() == RES); jacobians_.clear(); @@ -2486,17 +2486,17 @@ class FactorAutodiff<FacT,RES,B0,B1,0,0,0,0,0,0,0,0,0,0> : public FactorBase // std::cout << jacobians_[i] << std::endl << std::endl; } - virtual std::vector<StateBlockPtr> getStateBlockPtrVector() const + std::vector<StateBlockPtr> getStateBlockPtrVector() const override { return state_ptrs_; } - virtual std::vector<unsigned int> getStateSizes() const + std::vector<unsigned int> getStateSizes() const override { return state_block_sizes_; } - virtual unsigned int getSize() const + unsigned int getSize() const override { return RES; } @@ -2561,16 +2561,16 @@ class FactorAutodiff<FacT,RES,B0,0,0,0,0,0,0,0,0,0,0,0> : public FactorBase state_ptrs_.resize(n_blocks); } - virtual ~FactorAutodiff() + ~FactorAutodiff() override { } - virtual JacobianMethod getJacobianMethod() const + JacobianMethod getJacobianMethod() const override { return JAC_AUTO; } - virtual bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const + bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const override { // only residuals if (jacobians == nullptr) @@ -2612,7 +2612,7 @@ class FactorAutodiff<FacT,RES,B0,0,0,0,0,0,0,0,0,0,0,0> : public FactorBase jets_0_[i].a = parameters[0][i]; } - virtual void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const + void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const override { assert(residual_.size() == RES); jacobians_.clear(); @@ -2650,17 +2650,17 @@ class FactorAutodiff<FacT,RES,B0,0,0,0,0,0,0,0,0,0,0,0> : public FactorBase // std::cout << jacobians_[i] << std::endl << std::endl; } - virtual std::vector<StateBlockPtr> getStateBlockPtrVector() const + std::vector<StateBlockPtr> getStateBlockPtrVector() const override { return state_ptrs_; } - virtual std::vector<unsigned int> getStateSizes() const + std::vector<unsigned int> getStateSizes() const override { return state_block_sizes_; } - virtual unsigned int getSize() const + unsigned int getSize() const override { return RES; } diff --git a/include/core/factor/factor_autodiff_distance_3d.h b/include/core/factor/factor_autodiff_distance_3d.h index 320f7ac270cdd151f078c520561e509f108296d8..bd0808978214570e80c02dae7e19a4ec5b96129c 100644 --- a/include/core/factor/factor_autodiff_distance_3d.h +++ b/include/core/factor/factor_autodiff_distance_3d.h @@ -37,9 +37,9 @@ class FactorAutodiffDistance3d : public FactorAutodiff<FactorAutodiffDistance3d, { } - virtual ~FactorAutodiffDistance3d() { /* nothing */ } + ~FactorAutodiffDistance3d() override { /* nothing */ } - virtual std::string getTopology() const override + std::string getTopology() const override { return std::string("GEOM"); } diff --git a/include/core/factor/factor_base.h b/include/core/factor/factor_base.h index acbe45ec5d827c247376a130d0f5de5591c1bed3..1d4f01a35e5a1541ec6b147ab3155d268a7f9a9c 100644 --- a/include/core/factor/factor_base.h +++ b/include/core/factor/factor_base.h @@ -56,7 +56,7 @@ class FactorBase : public NodeBase, public std::enable_shared_from_this<FactorBa Eigen::VectorXd measurement_; ///< the measurement vector Eigen::MatrixXd measurement_sqrt_information_upper_;///< the squared root information matrix ///< ProcessorBase pointer list - virtual void setProblem(ProblemPtr) final; + void setProblem(ProblemPtr) override final; public: /** \brief Default constructor. @@ -87,7 +87,7 @@ class FactorBase : public NodeBase, public std::enable_shared_from_this<FactorBa - virtual ~FactorBase() = default; + ~FactorBase() override = default; virtual void remove(bool viral_remove_empty_parent=false); diff --git a/include/core/factor/factor_block_absolute.h b/include/core/factor/factor_block_absolute.h index 143308af2988a74d754f865c305e1ba089f4f778..21e2074e231488ee36bbc587b732b732d0483d0a 100644 --- a/include/core/factor/factor_block_absolute.h +++ b/include/core/factor/factor_block_absolute.h @@ -98,9 +98,9 @@ class FactorBlockAbsolute : public FactorAnalytic } } - virtual ~FactorBlockAbsolute() = default; + ~FactorBlockAbsolute() override = default; - virtual std::string getTopology() const override + std::string getTopology() const override { return std::string("ABS"); } @@ -110,7 +110,7 @@ class FactorBlockAbsolute : public FactorAnalytic * Returns the residual evaluated in the states provided in std::vector of mapped Eigen::VectorXd * **/ - virtual Eigen::VectorXd evaluateResiduals(const std::vector<Eigen::Map<const Eigen::VectorXd> >& _st_vector) const override; + Eigen::VectorXd evaluateResiduals(const std::vector<Eigen::Map<const Eigen::VectorXd> >& _st_vector) const override; /** \brief Returns the normalized jacobians evaluated in the states * @@ -122,10 +122,10 @@ class FactorBlockAbsolute : public FactorAnalytic * \param _compute_jacobian is a vector that specifies whether the ith jacobian sould be computed or not * **/ - virtual void evaluateJacobians(const std::vector<Eigen::Map<const Eigen::VectorXd>>& _st_vector, + void evaluateJacobians(const std::vector<Eigen::Map<const Eigen::VectorXd>>& _st_vector, std::vector<Eigen::Map<Eigen::MatrixRowXd> >& jacobians, const std::vector<bool>& _compute_jacobian) const override; - virtual void evaluateJacobians(const std::vector<Eigen::Map<const Eigen::VectorXd>>& _st_vector, + void evaluateJacobians(const std::vector<Eigen::Map<const Eigen::VectorXd>>& _st_vector, std::vector<Eigen::MatrixXd>& jacobians, const std::vector<bool>& _compute_jacobian) const override; @@ -136,11 +136,11 @@ class FactorBlockAbsolute : public FactorAnalytic * \param jacobians is an output vector of mapped eigen matrices that sould contain the jacobians w.r.t each state block * **/ - virtual void evaluatePureJacobians(std::vector<Eigen::MatrixXd>& jacobians) const override; + void evaluatePureJacobians(std::vector<Eigen::MatrixXd>& jacobians) const override; /** \brief Returns the factor residual size **/ - virtual unsigned int getSize() const override; + unsigned int getSize() const override; }; inline Eigen::VectorXd FactorBlockAbsolute::evaluateResiduals(const std::vector<Eigen::Map<const Eigen::VectorXd> >& _st_vector) const diff --git a/include/core/factor/factor_block_difference.h b/include/core/factor/factor_block_difference.h index ebaf8bc7be42c444f74588599e5b18d7135a5a88..d632a79871091ec67c63b8bd0e61f5e368f27320 100644 --- a/include/core/factor/factor_block_difference.h +++ b/include/core/factor/factor_block_difference.h @@ -81,9 +81,9 @@ class FactorBlockDifference : public FactorAnalytic J_res_sb2_.middleCols(sb2_constrained_start_,sb1_constrained_size_) = - Eigen::MatrixXd::Identity(sb2_constrained_size_,sb2_constrained_size_); } - virtual ~FactorBlockDifference() = default; + ~FactorBlockDifference() override = default; - virtual std::string getTopology() const override + std::string getTopology() const override { return std::string("DIFF"); } @@ -93,7 +93,7 @@ class FactorBlockDifference : public FactorAnalytic * Returns the residual evaluated in the states provided in std::vector of mapped Eigen::VectorXd * **/ - virtual Eigen::VectorXd evaluateResiduals(const std::vector<Eigen::Map<const Eigen::VectorXd> >& _st_vector) const override; + Eigen::VectorXd evaluateResiduals(const std::vector<Eigen::Map<const Eigen::VectorXd> >& _st_vector) const override; /** \brief Returns the normalized jacobians evaluated in the states * @@ -105,10 +105,10 @@ class FactorBlockDifference : public FactorAnalytic * \param _compute_jacobian is a vector that specifies whether the ith jacobian sould be computed or not * **/ - virtual void evaluateJacobians(const std::vector<Eigen::Map<const Eigen::VectorXd>>& _st_vector, + void evaluateJacobians(const std::vector<Eigen::Map<const Eigen::VectorXd>>& _st_vector, std::vector<Eigen::Map<Eigen::MatrixRowXd> >& jacobians, const std::vector<bool>& _compute_jacobian) const override; - virtual void evaluateJacobians(const std::vector<Eigen::Map<const Eigen::VectorXd>>& _st_vector, + void evaluateJacobians(const std::vector<Eigen::Map<const Eigen::VectorXd>>& _st_vector, std::vector<Eigen::MatrixXd>& jacobians, const std::vector<bool>& _compute_jacobian) const override; @@ -119,11 +119,11 @@ class FactorBlockDifference : public FactorAnalytic * \param jacobians is an output vector of mapped eigen matrices that sould contain the jacobians w.r.t each state block * **/ - virtual void evaluatePureJacobians(std::vector<Eigen::MatrixXd>& jacobians) const override; + void evaluatePureJacobians(std::vector<Eigen::MatrixXd>& jacobians) const override; /** \brief Returns the factor residual size **/ - virtual unsigned int getSize() const override; + unsigned int getSize() const override; }; inline Eigen::VectorXd FactorBlockDifference::evaluateResiduals(const std::vector<Eigen::Map<const Eigen::VectorXd> >& _st_vector) const diff --git a/include/core/factor/factor_diff_drive.h b/include/core/factor/factor_diff_drive.h index e267fb507ebfd811a0c17b1b6446267223510198..aa28c9eee91dfd6e8ed392ad0361952d87f8f0b4 100644 --- a/include/core/factor/factor_diff_drive.h +++ b/include/core/factor/factor_diff_drive.h @@ -80,9 +80,9 @@ class FactorDiffDrive : public FactorAutodiff<FactorDiffDrive, * Default destructor. * **/ - virtual ~FactorDiffDrive() = default; + ~FactorDiffDrive() override = default; - virtual std::string getTopology() const override + std::string getTopology() const override { return std::string("MOTION"); } diff --git a/include/core/factor/factor_odom_2d.h b/include/core/factor/factor_odom_2d.h index d8cfa08a9a9bf70c8b580f407f0983f60e791566..298cc35840163d92a353a450ed118360e2acf3d5 100644 --- a/include/core/factor/factor_odom_2d.h +++ b/include/core/factor/factor_odom_2d.h @@ -34,9 +34,9 @@ class FactorOdom2d : public FactorAutodiff<FactorOdom2d, 3, 2, 1, 2, 1> // } - virtual ~FactorOdom2d() = default; + ~FactorOdom2d() override = default; - virtual std::string getTopology() const override + std::string getTopology() const override { return std::string("MOTION"); } diff --git a/include/core/factor/factor_odom_2d_analytic.h b/include/core/factor/factor_odom_2d_analytic.h index 52ea04ccd817f2a6c914d771737c284bca4ce664..dc1437e4fe441c8c9a6e9406097ac757f56d8c03 100644 --- a/include/core/factor/factor_odom_2d_analytic.h +++ b/include/core/factor/factor_odom_2d_analytic.h @@ -28,9 +28,9 @@ class FactorOdom2dAnalytic : public FactorRelative2dAnalytic // } - virtual ~FactorOdom2dAnalytic() = default; + ~FactorOdom2dAnalytic() override = default; - virtual std::string getTopology() const override + std::string getTopology() const override { return std::string("MOTION"); } diff --git a/include/core/factor/factor_odom_2d_closeloop.h b/include/core/factor/factor_odom_2d_closeloop.h index a4ea7b1dff8484a89885edd424a6ac899331d3d7..16f1d677024f4dd97968dbfda45c0e3aaca82723 100644 --- a/include/core/factor/factor_odom_2d_closeloop.h +++ b/include/core/factor/factor_odom_2d_closeloop.h @@ -35,7 +35,7 @@ class FactorOdom2dCloseloop : public FactorAutodiff<FactorOdom2dCloseloop, 3, 2, virtual ~FactorOdom2dCloseloop() = default; - virtual std::string getTopology() const override + std::string getTopology() const override { return std::string("LOOP"); } diff --git a/include/core/factor/factor_odom_3d.h b/include/core/factor/factor_odom_3d.h index 4e32efe4067d52c23bfe978cea7ef792214e00c9..94b117f21298ebcffac648214f5946e2f6b486ce 100644 --- a/include/core/factor/factor_odom_3d.h +++ b/include/core/factor/factor_odom_3d.h @@ -26,9 +26,9 @@ class FactorOdom3d : public FactorAutodiff<FactorOdom3d,6,3,4,3,4> bool _apply_loss_function, FactorStatus _status = FAC_ACTIVE); - virtual ~FactorOdom3d() = default; + ~FactorOdom3d() override = default; - virtual std::string getTopology() const override + std::string getTopology() const override { return std::string("MOTION"); } diff --git a/include/core/factor/factor_pose_2d.h b/include/core/factor/factor_pose_2d.h index a054c11673b75e69fe413afa9c5a161ac42d0778..6536dff686069f44f52be6683d7c140f1ce176c9 100644 --- a/include/core/factor/factor_pose_2d.h +++ b/include/core/factor/factor_pose_2d.h @@ -32,9 +32,9 @@ class FactorPose2d: public FactorAutodiff<FactorPose2d,3,2,1> // std::cout << "created FactorPose2d " << std::endl; } - virtual ~FactorPose2d() = default; + ~FactorPose2d() override = default; - virtual std::string getTopology() const override + std::string getTopology() const override { return std::string("ABS"); } diff --git a/include/core/factor/factor_pose_3d.h b/include/core/factor/factor_pose_3d.h index 0390ab6401f782ed30921e9090bc2e5ed796589a..dfc8a17544c75007a5f6815248680be0e47dd5c9 100644 --- a/include/core/factor/factor_pose_3d.h +++ b/include/core/factor/factor_pose_3d.h @@ -31,9 +31,9 @@ class FactorPose3d: public FactorAutodiff<FactorPose3d,6,3,4> // } - virtual ~FactorPose3d() = default; + ~FactorPose3d() override = default; - virtual std::string getTopology() const override + std::string getTopology() const override { return std::string("ABS"); } diff --git a/include/core/factor/factor_quaternion_absolute.h b/include/core/factor/factor_quaternion_absolute.h index 8cb37c39234d4ae47c05453179f0354380c824e9..6e966fbc69d2eabb5f809ed4f8d3450634771a20 100644 --- a/include/core/factor/factor_quaternion_absolute.h +++ b/include/core/factor/factor_quaternion_absolute.h @@ -42,9 +42,9 @@ class FactorQuaternionAbsolute: public FactorAutodiff<FactorQuaternionAbsolute,3 // } - virtual ~FactorQuaternionAbsolute() = default; + ~FactorQuaternionAbsolute() override = default; - virtual std::string getTopology() const override + std::string getTopology() const override { return std::string("ABS"); } diff --git a/include/core/factor/factor_relative_2d_analytic.h b/include/core/factor/factor_relative_2d_analytic.h index e4ccf958c00e0e6185e0cf97a20c8072517c2756..dfb06c429b10e205ffe93146269f32a05d664a7d 100644 --- a/include/core/factor/factor_relative_2d_analytic.h +++ b/include/core/factor/factor_relative_2d_analytic.h @@ -91,16 +91,16 @@ class FactorRelative2dAnalytic : public FactorAnalytic // } - virtual std::string getTopology() const override + std::string getTopology() const override { return std::string("GEOM"); } - virtual ~FactorRelative2dAnalytic() = default; + ~FactorRelative2dAnalytic() override = default; /** \brief Returns the factor residual size **/ - virtual unsigned int getSize() const override + unsigned int getSize() const override { return 3; } @@ -109,7 +109,7 @@ class FactorRelative2dAnalytic : public FactorAnalytic * * Returns the residual evaluated in the states provided in a std::vector of mapped Eigen::VectorXd **/ - virtual Eigen::VectorXd evaluateResiduals( + Eigen::VectorXd evaluateResiduals( const std::vector<Eigen::Map<const Eigen::VectorXd> >& _st_vector) const override; /** \brief Returns the jacobians evaluated in the states provided @@ -122,10 +122,10 @@ class FactorRelative2dAnalytic : public FactorAnalytic * \param _compute_jacobian is a vector that specifies whether the ith jacobian sould be computed or not * **/ - virtual void evaluateJacobians(const std::vector<Eigen::Map<const Eigen::VectorXd>>& _st_vector, + void evaluateJacobians(const std::vector<Eigen::Map<const Eigen::VectorXd>>& _st_vector, std::vector<Eigen::Map<Eigen::MatrixRowXd> >& jacobians, const std::vector<bool>& _compute_jacobian) const override; - virtual void evaluateJacobians(const std::vector<Eigen::Map<const Eigen::VectorXd>>& _st_vector, + void evaluateJacobians(const std::vector<Eigen::Map<const Eigen::VectorXd>>& _st_vector, std::vector<Eigen::MatrixXd>& jacobians, const std::vector<bool>& _compute_jacobian) const override; @@ -133,7 +133,7 @@ class FactorRelative2dAnalytic : public FactorAnalytic * \param jacobians is an output vector of mapped eigen matrices that sould contain the jacobians w.r.t each state block * **/ - virtual void evaluatePureJacobians(std::vector<Eigen::MatrixXd>& jacobians) const override; + void evaluatePureJacobians(std::vector<Eigen::MatrixXd>& jacobians) const override; }; diff --git a/include/core/factor/factor_relative_pose_2d_with_extrinsics.h b/include/core/factor/factor_relative_pose_2d_with_extrinsics.h index 704cc3e7bc906a84a6702b6e8fdcad38766562ee..1ce6c842b77561fb95a154ea6af623e333045a63 100644 --- a/include/core/factor/factor_relative_pose_2d_with_extrinsics.h +++ b/include/core/factor/factor_relative_pose_2d_with_extrinsics.h @@ -39,9 +39,9 @@ class FactorRelativePose2dWithExtrinsics : public FactorAutodiff<FactorRelativeP // } - virtual ~FactorRelativePose2dWithExtrinsics() = default; + ~FactorRelativePose2dWithExtrinsics() override = default; - virtual std::string getTopology() const override + std::string getTopology() const override { return std::string("MOTION"); } diff --git a/include/core/feature/feature_base.h b/include/core/feature/feature_base.h index f412fd3688e114e6116cd17db7de724e0fb7fa85..43735ff44e297f6e6b71a43122d8e6a71387b340 100644 --- a/include/core/feature/feature_base.h +++ b/include/core/feature/feature_base.h @@ -37,7 +37,7 @@ class FeatureBase : public NodeBase, public std::enable_shared_from_this<Feature Eigen::MatrixXd measurement_covariance_; ///< the measurement covariance matrix Eigen::MatrixXd measurement_sqrt_information_upper_; ///< the squared root information matrix Eigen::VectorXd expectation_; ///< expectation - virtual void setProblem(ProblemPtr _problem) final; + void setProblem(ProblemPtr _problem) override final; public: @@ -58,7 +58,7 @@ class FeatureBase : public NodeBase, public std::enable_shared_from_this<Feature const Eigen::MatrixXd& _meas_uncertainty, UncertaintyType _uncertainty_type = UNCERTAINTY_IS_COVARIANCE); - virtual ~FeatureBase(); + ~FeatureBase() override; virtual void remove(bool viral_remove_empty_parent=false); diff --git a/include/core/feature/feature_motion.h b/include/core/feature/feature_motion.h index ae588e29a7a6ad8de83b601b87af7c41903d33c9..0f5ecc2a66930370b3a314a1284ff366fc76434f 100644 --- a/include/core/feature/feature_motion.h +++ b/include/core/feature/feature_motion.h @@ -24,7 +24,7 @@ class FeatureMotion : public FeatureBase const MatrixXd _delta_preint_cov, const VectorXd& _calib_preint, const MatrixXd& _jacobian_calib); - virtual ~FeatureMotion(); + ~FeatureMotion() override; const Eigen::VectorXd& getDeltaPreint() const; ///< A new name for getMeasurement() const Eigen::VectorXd& getCalibrationPreint() const; diff --git a/include/core/feature/feature_odom_2d.h b/include/core/feature/feature_odom_2d.h index 9ef3059cd8afb11ea7cdf994b46b2f66ad344723..cb65fa06b01d72cb32d1209752b44d6826f0d76b 100644 --- a/include/core/feature/feature_odom_2d.h +++ b/include/core/feature/feature_odom_2d.h @@ -25,7 +25,7 @@ class FeatureOdom2d : public FeatureBase */ FeatureOdom2d(const Eigen::VectorXd& _measurement, const Eigen::MatrixXd& _meas_covariance); - virtual ~FeatureOdom2d(); + ~FeatureOdom2d() override; /** \brief Generic interface to find factors * diff --git a/include/core/feature/feature_pose.h b/include/core/feature/feature_pose.h index 2da7d5b8f367323d756a9dc32d080e25c5e9d254..701967949c395fa02371f55d9313c508174eabeb 100644 --- a/include/core/feature/feature_pose.h +++ b/include/core/feature/feature_pose.h @@ -23,7 +23,7 @@ class FeaturePose : public FeatureBase * */ FeaturePose(const Eigen::VectorXd& _measurement, const Eigen::MatrixXd& _meas_covariance); - virtual ~FeaturePose(); + ~FeaturePose() override; }; } // namespace wolf diff --git a/include/core/frame/frame_base.h b/include/core/frame/frame_base.h index 6c73ad933f4b305fca0c71af6db5a47792cab574..5c45c103c33b77542a1d136b870d6a0f88c177eb 100644 --- a/include/core/frame/frame_base.h +++ b/include/core/frame/frame_base.h @@ -79,7 +79,7 @@ class FrameBase : public NodeBase, public HasStateBlocks, public std::enable_sha const std::string _frame_structure, const std::list<VectorXd>& _vectors); - virtual ~FrameBase(); + ~FrameBase() override; virtual void remove(bool viral_remove_empty_parent=false); // Frame properties ----------------------------------------------- @@ -109,7 +109,7 @@ class FrameBase : public NodeBase, public HasStateBlocks, public std::enable_sha StateBlockPtr getV() const; protected: - virtual void setProblem(ProblemPtr _problem) final; + void setProblem(ProblemPtr _problem) override final; // States public: diff --git a/include/core/hardware/hardware_base.h b/include/core/hardware/hardware_base.h index fba575b0b8ea55a15b8bbe4972d0bc12984ae62b..0ef770b1cb1249491c01329b9ecc4952776a9dd3 100644 --- a/include/core/hardware/hardware_base.h +++ b/include/core/hardware/hardware_base.h @@ -23,7 +23,7 @@ class HardwareBase : public NodeBase, public std::enable_shared_from_this<Hardwa public: HardwareBase(); - virtual ~HardwareBase(); + ~HardwareBase() override; const SensorBasePtrList& getSensorList() const; diff --git a/include/core/landmark/landmark_base.h b/include/core/landmark/landmark_base.h index 3d177d79c972b1e072fb86d5d7790e686cd387ff..21098d33232129521a5d4f56b52db1930feb5eee 100644 --- a/include/core/landmark/landmark_base.h +++ b/include/core/landmark/landmark_base.h @@ -34,7 +34,7 @@ class LandmarkBase : public NodeBase, public HasStateBlocks, public std::enable_ protected: // Navigate wolf tree - virtual void setProblem(ProblemPtr _problem) final; + void setProblem(ProblemPtr _problem) override final; unsigned int landmark_id_; ///< landmark unique id TimeStamp stamp_; ///< stamp of the creation of the landmark Eigen::VectorXd descriptor_; //TODO: agree? JS: No: It is not general enough as descriptor to be in LmkBase. @@ -50,7 +50,7 @@ class LandmarkBase : public NodeBase, public HasStateBlocks, public std::enable_ * **/ LandmarkBase(const std::string& _type, StateBlockPtr _p_ptr, StateBlockPtr _o_ptr = nullptr); - virtual ~LandmarkBase(); + ~LandmarkBase() override; virtual void remove(bool viral_remove_empty_parent=false); virtual YAML::Node saveToYaml() const; diff --git a/include/core/map/map_base.h b/include/core/map/map_base.h index e609298014d8b68ca9e686a877ea80b041b34214..caac2f94eed78b033c153373f5d25f101fc2d833 100644 --- a/include/core/map/map_base.h +++ b/include/core/map/map_base.h @@ -26,7 +26,7 @@ class MapBase : public NodeBase, public std::enable_shared_from_this<MapBase> public: MapBase(); - ~MapBase(); + ~MapBase() override; private: virtual LandmarkBasePtr addLandmark(LandmarkBasePtr _landmark_ptr); diff --git a/include/core/processor/processor_base.h b/include/core/processor/processor_base.h index 4182e762db050a3f36e714d453b73fb63568f5bc..dd4c37b277a514f40051ee96de70ab04cfe43c62 100644 --- a/include/core/processor/processor_base.h +++ b/include/core/processor/processor_base.h @@ -221,7 +221,7 @@ struct ParamsProcessorBase : public ParamsBase apply_loss_function = _server.getParam<bool>(prefix + _unique_name + "/apply_loss_function"); } - virtual ~ParamsProcessorBase() = default; + ~ParamsProcessorBase() override = default; /** maximum time difference between a Keyframe time stamp and * a particular Capture of this processor to allow assigning @@ -259,7 +259,7 @@ class ProcessorBase : public NodeBase, public std::enable_shared_from_this<Proce public: ProcessorBase(const std::string& _type, int _dim, ParamsProcessorBasePtr _params); - virtual ~ProcessorBase(); + ~ProcessorBase() override; virtual void configure(SensorBasePtr _sensor) = 0; virtual void remove(); @@ -326,7 +326,7 @@ class ProcessorBase : public NodeBase, public std::enable_shared_from_this<Proce virtual bool permittedAuxFrame() final; - virtual void setProblem(ProblemPtr) override; + void setProblem(ProblemPtr) override; public: /**\brief notify a new keyframe made by another processor diff --git a/include/core/processor/processor_diff_drive.h b/include/core/processor/processor_diff_drive.h index e3e504f36b50d95c69bf13d0a99c0107f5207b27..e50b2f55764cbc2a5570a4192ed8c15f560804fe 100644 --- a/include/core/processor/processor_diff_drive.h +++ b/include/core/processor/processor_diff_drive.h @@ -34,22 +34,22 @@ class ProcessorDiffDrive : public ProcessorOdom2d { public: ProcessorDiffDrive(ParamsProcessorDiffDrivePtr _params_motion); - virtual ~ProcessorDiffDrive(); - virtual void configure(SensorBasePtr _sensor) override; + ~ProcessorDiffDrive() override; + void configure(SensorBasePtr _sensor) override; // Factory method for high level API WOLF_PROCESSOR_CREATE(ProcessorDiffDrive, ParamsProcessorDiffDrive); protected: // Motion integration - virtual void computeCurrentDelta(const Eigen::VectorXd& _data, + void computeCurrentDelta(const Eigen::VectorXd& _data, const Eigen::MatrixXd& _data_cov, const Eigen::VectorXd& _calib, const double _dt, Eigen::VectorXd& _delta, Eigen::MatrixXd& _delta_cov, Eigen::MatrixXd& _jacobian_calib) const override; - virtual CaptureMotionPtr emplaceCapture(const FrameBasePtr& _frame_own, + CaptureMotionPtr emplaceCapture(const FrameBasePtr& _frame_own, const SensorBasePtr& _sensor, const TimeStamp& _ts, const VectorXd& _data, @@ -57,11 +57,11 @@ class ProcessorDiffDrive : public ProcessorOdom2d const VectorXd& _calib, const VectorXd& _calib_preint, const CaptureBasePtr& _capture_origin) override; - virtual FeatureBasePtr emplaceFeature(CaptureMotionPtr _capture_own) override; - virtual FactorBasePtr emplaceFactor(FeatureBasePtr _feature_motion, + FeatureBasePtr emplaceFeature(CaptureMotionPtr _capture_own) override; + FactorBasePtr emplaceFactor(FeatureBasePtr _feature_motion, CaptureBasePtr _capture_origin) override; - virtual VectorXd getCalibration (const CaptureBasePtr _capture) const override; - virtual void setCalibration(const CaptureBasePtr _capture, const VectorXd& _calibration) override; + VectorXd getCalibration (const CaptureBasePtr _capture) const override; + void setCalibration(const CaptureBasePtr _capture, const VectorXd& _calibration) override; protected: ParamsProcessorDiffDrivePtr params_prc_diff_drv_selfcal_; diff --git a/include/core/processor/processor_loopclosure.h b/include/core/processor/processor_loopclosure.h index 4b22ba3985cf04a1c5c1f7658419ea9ed384f390..12e1fd8781627154315b4815a86105e1d404e86f 100644 --- a/include/core/processor/processor_loopclosure.h +++ b/include/core/processor/processor_loopclosure.h @@ -52,46 +52,46 @@ public: ProcessorLoopClosure(const std::string& _type, int _dim, ParamsProcessorLoopClosurePtr _params_loop_closure); - virtual ~ProcessorLoopClosure() = default; - virtual void configure(SensorBasePtr _sensor) override { }; + ~ProcessorLoopClosure() override = default; + void configure(SensorBasePtr _sensor) override { }; protected: /** \brief process an incoming capture * * The ProcessorLoopClosure is only triggered in KF (see triggerInCapture()) so this function is not called. */ - virtual void processCapture(CaptureBasePtr) override {}; + void processCapture(CaptureBasePtr) override {}; /** \brief process an incoming key-frame * * Each derived processor should implement this function. It will be called if: * - A new KF arrived and triggerInKF() returned true. */ - virtual void processKeyFrame(FrameBasePtr _keyframe_ptr, const double& _time_tolerance) override; + void processKeyFrame(FrameBasePtr _keyframe_ptr, const double& _time_tolerance) override; /** \brief trigger in capture * * The ProcessorLoopClosure only processes incoming KF, then it returns false. */ - virtual bool triggerInCapture(CaptureBasePtr) const override {return false;} + bool triggerInCapture(CaptureBasePtr) const override {return false;} /** \brief trigger in key-frame * * Returns true if processKeyFrame() should be called after the provided KF arrived. */ - virtual bool triggerInKeyFrame(FrameBasePtr _keyframe_ptr, const double& _time_tol_other) const override; + bool triggerInKeyFrame(FrameBasePtr _keyframe_ptr, const double& _time_tol_other) const override; /** \brief store key frame * * Returns true if the key frame should be stored */ - virtual bool storeKeyFrame(FrameBasePtr) override; + bool storeKeyFrame(FrameBasePtr) override; /** \brief store capture * * Returns true if the capture should be stored */ - virtual bool storeCapture(CaptureBasePtr) override; + bool storeCapture(CaptureBasePtr) override; /** \brief Called by process(). Tells if computeFeatures() will be called */ @@ -172,7 +172,7 @@ protected: * * WARNING! This function only votes! It does not create KeyFrames! */ - virtual bool voteForKeyFrame() const override + bool voteForKeyFrame() const override { return false; }; diff --git a/include/core/processor/processor_motion.h b/include/core/processor/processor_motion.h index 8533e66caf5da96a06680098b44236a4fb420482..953b9723bd362fbdca73fb7010cf3d8919684a0c 100644 --- a/include/core/processor/processor_motion.h +++ b/include/core/processor/processor_motion.h @@ -159,15 +159,15 @@ class ProcessorMotion : public ProcessorBase, public IsMotion SizeEigen _data_size, SizeEigen _calib_size, ParamsProcessorMotionPtr _params_motion); - virtual ~ProcessorMotion(); + ~ProcessorMotion() override; // Instructions to the processor: virtual void resetDerived(); // Queries to the processor: - virtual TimeStamp getTimeStamp() const override; - virtual VectorComposite getState() const override; - virtual VectorComposite getState(const TimeStamp& _ts) const override; + TimeStamp getTimeStamp() const override; + VectorComposite getState() const override; + VectorComposite getState(const TimeStamp& _ts) const override; /** \brief Gets the delta preintegrated covariance from all integrations so far * \return the delta preintegrated covariance matrix @@ -211,39 +211,39 @@ class ProcessorMotion : public ProcessorBase, public IsMotion * Each derived processor should implement this function. It will be called if: * - A new capture arrived and triggerInCapture() returned true. */ - virtual void processCapture(CaptureBasePtr) override; + void processCapture(CaptureBasePtr) override; /** \brief process an incoming key-frame * * The ProcessorMotion only processes incoming captures (it is not called). */ - virtual void processKeyFrame(FrameBasePtr _keyframe_ptr, const double& _time_tol_other) override {}; + void processKeyFrame(FrameBasePtr _keyframe_ptr, const double& _time_tol_other) override {}; /** \brief trigger in capture * * Returns true if processCapture() should be called after the provided capture arrived. */ - virtual bool triggerInCapture(CaptureBasePtr) const override {return true;} + bool triggerInCapture(CaptureBasePtr) const override {return true;} /** \brief trigger in key-frame * * The ProcessorMotion only processes incoming captures, then it returns false. */ - virtual bool triggerInKeyFrame(FrameBasePtr _keyframe_ptr, const double& _time_tol_other) const override {return false;} + bool triggerInKeyFrame(FrameBasePtr _keyframe_ptr, const double& _time_tol_other) const override {return false;} /** \brief store key frame * * Returns true if the key frame should be stored */ - virtual bool storeKeyFrame(FrameBasePtr) override; + bool storeKeyFrame(FrameBasePtr) override; /** \brief store capture * * Returns true if the capture should be stored */ - virtual bool storeCapture(CaptureBasePtr) override; + bool storeCapture(CaptureBasePtr) override; - virtual bool voteForKeyFrame() const override; + bool voteForKeyFrame() const override; double updateDt(); void integrateOneStep(); diff --git a/include/core/processor/processor_odom_2d.h b/include/core/processor/processor_odom_2d.h index 0b873564bb7339e9acf63f1739076b9baa4ec29a..de3aebb4a811e954a27f4ac24c22dd277d9142fd 100644 --- a/include/core/processor/processor_odom_2d.h +++ b/include/core/processor/processor_odom_2d.h @@ -42,41 +42,41 @@ class ProcessorOdom2d : public ProcessorMotion { public: ProcessorOdom2d(ParamsProcessorOdom2dPtr _params); - virtual ~ProcessorOdom2d(); - virtual void configure(SensorBasePtr _sensor) override { }; + ~ProcessorOdom2d() override; + void configure(SensorBasePtr _sensor) override { }; // Factory method for high level API WOLF_PROCESSOR_CREATE(ProcessorOdom2d, ParamsProcessorOdom2d); - virtual bool voteForKeyFrame() const override; + bool voteForKeyFrame() const override; protected: - virtual void computeCurrentDelta(const Eigen::VectorXd& _data, + void computeCurrentDelta(const Eigen::VectorXd& _data, const Eigen::MatrixXd& _data_cov, const Eigen::VectorXd& _calib, const double _dt, Eigen::VectorXd& _delta, Eigen::MatrixXd& _delta_cov, Eigen::MatrixXd& _jacobian_calib) const override; - virtual void deltaPlusDelta(const Eigen::VectorXd& _delta1, + void deltaPlusDelta(const Eigen::VectorXd& _delta1, const Eigen::VectorXd& _delta2, const double _Dt2, Eigen::VectorXd& _delta1_plus_delta2) const override; - virtual void deltaPlusDelta(const Eigen::VectorXd& _delta1, + void deltaPlusDelta(const Eigen::VectorXd& _delta1, const Eigen::VectorXd& _delta2, const double _Dt2, Eigen::VectorXd& _delta1_plus_delta2, Eigen::MatrixXd& _jacobian1, Eigen::MatrixXd& _jacobian2) const override; - virtual void statePlusDelta(const VectorComposite& _x, + void statePlusDelta(const VectorComposite& _x, const Eigen::VectorXd& _delta, const double _Dt, VectorComposite& _x_plus_delta) const override; - virtual Eigen::VectorXd deltaZero() const override; + Eigen::VectorXd deltaZero() const override; Eigen::VectorXd correctDelta(const Eigen::VectorXd& delta_preint, const Eigen::VectorXd& delta_step) const override; - virtual CaptureMotionPtr emplaceCapture(const FrameBasePtr& _frame_own, + CaptureMotionPtr emplaceCapture(const FrameBasePtr& _frame_own, const SensorBasePtr& _sensor, const TimeStamp& _ts, const VectorXd& _data, @@ -84,11 +84,11 @@ class ProcessorOdom2d : public ProcessorMotion const VectorXd& _calib, const VectorXd& _calib_preint, const CaptureBasePtr& _capture_origin_ptr) override; - virtual FeatureBasePtr emplaceFeature(CaptureMotionPtr _capture_motion) override; - virtual FactorBasePtr emplaceFactor(FeatureBasePtr _feature, + FeatureBasePtr emplaceFeature(CaptureMotionPtr _capture_motion) override; + FactorBasePtr emplaceFactor(FeatureBasePtr _feature, CaptureBasePtr _capture_origin) override; - virtual VectorXd getCalibration (const CaptureBasePtr _capture) const override; - virtual void setCalibration(const CaptureBasePtr _capture, const VectorXd& _calibration) override; + VectorXd getCalibration (const CaptureBasePtr _capture) const override; + void setCalibration(const CaptureBasePtr _capture, const VectorXd& _calibration) override; protected: ParamsProcessorOdom2dPtr params_odom_2d_; diff --git a/include/core/processor/processor_odom_3d.h b/include/core/processor/processor_odom_3d.h index 49eaf4fad2788dde0499021ec89fb58d228cb65b..0ff94590e542afe465676b7332d23ad5064ee56e 100644 --- a/include/core/processor/processor_odom_3d.h +++ b/include/core/processor/processor_odom_3d.h @@ -61,15 +61,15 @@ class ProcessorOdom3d : public ProcessorMotion { public: ProcessorOdom3d(ParamsProcessorOdom3dPtr _params); - virtual ~ProcessorOdom3d(); - virtual void configure(SensorBasePtr _sensor) override; + ~ProcessorOdom3d() override; + void configure(SensorBasePtr _sensor) override; // Factory method for high level API WOLF_PROCESSOR_CREATE(ProcessorOdom3d, ParamsProcessorOdom3d); public: // Motion integration - virtual void computeCurrentDelta(const Eigen::VectorXd& _data, + void computeCurrentDelta(const Eigen::VectorXd& _data, const Eigen::MatrixXd& _data_cov, const Eigen::VectorXd& _calib, const double _dt, @@ -95,7 +95,7 @@ class ProcessorOdom3d : public ProcessorMotion const Eigen::VectorXd& delta_step) const override; bool voteForKeyFrame() const override; - virtual CaptureMotionPtr emplaceCapture(const FrameBasePtr& _frame_own, + CaptureMotionPtr emplaceCapture(const FrameBasePtr& _frame_own, const SensorBasePtr& _sensor, const TimeStamp& _ts, const VectorXd& _data, @@ -104,12 +104,12 @@ class ProcessorOdom3d : public ProcessorMotion const VectorXd& _calib_preint, const CaptureBasePtr& _capture_origin) override; - virtual FeatureBasePtr emplaceFeature(CaptureMotionPtr _capture_motion) override; + FeatureBasePtr emplaceFeature(CaptureMotionPtr _capture_motion) override; - virtual FactorBasePtr emplaceFactor(FeatureBasePtr _feature_motion, + FactorBasePtr emplaceFactor(FeatureBasePtr _feature_motion, CaptureBasePtr _capture_origin) override; - virtual VectorXd getCalibration (const CaptureBasePtr _capture) const override; - virtual void setCalibration(const CaptureBasePtr _capture, const VectorXd& _calibration) override; + VectorXd getCalibration (const CaptureBasePtr _capture) const override; + void setCalibration(const CaptureBasePtr _capture, const VectorXd& _calibration) override; protected: ParamsProcessorOdom3dPtr params_odom_3d_; diff --git a/include/core/processor/processor_tracker.h b/include/core/processor/processor_tracker.h index 0b7197574ae6a05064792dbabeaea9fd019abd0b..0f4c3180003140544f251113583e0184e630d9b8 100644 --- a/include/core/processor/processor_tracker.h +++ b/include/core/processor/processor_tracker.h @@ -112,7 +112,7 @@ class ProcessorTracker : public ProcessorBase const StateStructure& _structure, int _dim, ParamsProcessorTrackerPtr _params_tracker); - virtual ~ProcessorTracker(); + ~ProcessorTracker() override; StateStructure getStateStructure() const; @@ -131,37 +131,37 @@ class ProcessorTracker : public ProcessorBase * Each derived processor should implement this function. It will be called if: * - A new capture arrived and triggerInCapture() returned true. */ - virtual void processCapture(CaptureBasePtr) override; + void processCapture(CaptureBasePtr) override; /** \brief process an incoming key-frame * * The ProcessorTracker only processes incoming captures (it is not called). */ - virtual void processKeyFrame(FrameBasePtr _keyframe_ptr, const double& _time_tolerance) override {}; + void processKeyFrame(FrameBasePtr _keyframe_ptr, const double& _time_tolerance) override {}; /** \brief trigger in capture * * Returns true if processCapture() should be called after the provided capture arrived. */ - virtual bool triggerInCapture(CaptureBasePtr) const override; + bool triggerInCapture(CaptureBasePtr) const override; /** \brief trigger in key-frame * * The ProcessorTracker only processes incoming captures, then it returns false. */ - virtual bool triggerInKeyFrame(FrameBasePtr _keyframe_ptr, const double& _time_tolerance) const override {return false;} + bool triggerInKeyFrame(FrameBasePtr _keyframe_ptr, const double& _time_tolerance) const override {return false;} /** \brief store key frame * * Returns true if the key frame should be stored */ - virtual bool storeKeyFrame(FrameBasePtr) override; + bool storeKeyFrame(FrameBasePtr) override; /** \brief store capture * * Returns true if the capture should be stored */ - virtual bool storeCapture(CaptureBasePtr) override; + bool storeCapture(CaptureBasePtr) override; /** Pre-process incoming Capture * @@ -219,7 +219,7 @@ class ProcessorTracker : public ProcessorBase * * WARNING! This function only votes! It does not create KeyFrames! */ - virtual bool voteForKeyFrame() const override = 0; + bool voteForKeyFrame() const override = 0; /** \brief Advance the incoming Capture to become the last. * diff --git a/include/core/processor/processor_tracker_feature.h b/include/core/processor/processor_tracker_feature.h index b69599ef55fce9f4624b6fe9115722aeb86aa3ca..86fc8f35a78a78d882820f3512a6bcec12eeb193 100644 --- a/include/core/processor/processor_tracker_feature.h +++ b/include/core/processor/processor_tracker_feature.h @@ -88,7 +88,7 @@ class ProcessorTrackerFeature : public ProcessorTracker const StateStructure& _structure, int _dim, ParamsProcessorTrackerFeaturePtr _params_tracker_feature); - virtual ~ProcessorTrackerFeature(); + ~ProcessorTrackerFeature() override; protected: ParamsProcessorTrackerFeaturePtr params_tracker_feature_; @@ -112,7 +112,7 @@ class ProcessorTrackerFeature : public ProcessorTracker * - Create the factors, of the correct type, derived from FactorBase * (through FactorAnalytic or FactorSparse). */ - virtual unsigned int processKnown() override; + unsigned int processKnown() override; /** \brief Track provided features in \b _capture * \param _features_in input list of features in \b last to track @@ -148,16 +148,16 @@ class ProcessorTrackerFeature : public ProcessorTracker * * WARNING! This function only votes! It does not create KeyFrames! */ - virtual bool voteForKeyFrame() const override = 0; + bool voteForKeyFrame() const override = 0; // We overload the advance and reset functions to update the lists of matches - virtual void advanceDerived() override; - virtual void resetDerived() override; + void advanceDerived() override; + void resetDerived() override; /**\brief Process new Features * */ - virtual unsigned int processNew(const int& _max_features) override; + unsigned int processNew(const int& _max_features) override; /** \brief Detect new Features * \param _max_features maximum number of features detected (-1: unlimited. 0: none) @@ -191,7 +191,7 @@ class ProcessorTrackerFeature : public ProcessorTracker /** \brief Emplaces a new factor for each correspondence between a feature in Capture \b last and a feature in Capture \b origin */ - virtual void establishFactors() override; + void establishFactors() override; }; } // namespace wolf diff --git a/include/core/processor/processor_tracker_landmark.h b/include/core/processor/processor_tracker_landmark.h index 6181810bde23395d70c8e28cabc2457f4b13f41b..23f0b89fc03432ea411227ca9de85dc40407693e 100644 --- a/include/core/processor/processor_tracker_landmark.h +++ b/include/core/processor/processor_tracker_landmark.h @@ -83,7 +83,7 @@ class ProcessorTrackerLandmark : public ProcessorTracker ProcessorTrackerLandmark(const std::string& _type, const StateStructure& _structure, ParamsProcessorTrackerLandmarkPtr _params_tracker_landmark); - virtual ~ProcessorTrackerLandmark(); + ~ProcessorTrackerLandmark() override; protected: @@ -103,7 +103,7 @@ class ProcessorTrackerLandmark : public ProcessorTracker * The function must populate the list of Features in the \b incoming Capture. * Features need to be of the correct type, derived from FeatureBase. */ - virtual unsigned int processKnown(); + unsigned int processKnown() override; /** \brief Find provided landmarks as features in the provided capture * \param _landmarks_in input list of landmarks to be found @@ -130,16 +130,16 @@ class ProcessorTrackerLandmark : public ProcessorTracker * * WARNING! This function only votes! It does not create KeyFrames! */ - virtual bool voteForKeyFrame() const = 0; + bool voteForKeyFrame() const override = 0; // We overload the advance and reset functions to update the lists of matches - void advanceDerived(); - void resetDerived(); + void advanceDerived() override; + void resetDerived() override; /** \brief Process new Features * */ - unsigned int processNew(const int& _max_features); + unsigned int processNew(const int& _max_features) override; /** \brief Detect new Features * \param _max_features maximum number of features detected (-1: unlimited. 0: none) @@ -181,7 +181,7 @@ class ProcessorTrackerLandmark : public ProcessorTracker /** \brief Emplaces a new factor for each correspondence between a feature in Capture \b last and a landmark */ - virtual void establishFactors(); + void establishFactors() override; }; }// namespace wolf diff --git a/include/core/sensor/sensor_base.h b/include/core/sensor/sensor_base.h index e1be8095b90f395477ea72ed0302520fb0ae4bbb..d59daef943bffdc01e835453963f4dac8c7ad7df 100644 --- a/include/core/sensor/sensor_base.h +++ b/include/core/sensor/sensor_base.h @@ -74,7 +74,7 @@ SensorBasePtr create(const std::string& _unique_name, const Eigen::VectorXd& _ex struct ParamsSensorBase: public ParamsBase { std::string prefix = "sensor/"; - virtual ~ParamsSensorBase() = default; + ~ParamsSensorBase() override = default; using ParamsBase::ParamsBase; std::string print() const { @@ -104,7 +104,7 @@ class SensorBase : public NodeBase, public HasStateBlocks, public std::enable_sh Eigen::VectorXd noise_std_; // std of sensor noise Eigen::MatrixXd noise_cov_; // cov matrix of noise - virtual void setProblem(ProblemPtr _problem) final; + void setProblem(ProblemPtr _problem) override final; public: /** \brief Constructor with noise size @@ -151,7 +151,7 @@ class SensorBase : public NodeBase, public HasStateBlocks, public std::enable_sh const bool _o_dyn = false, const bool _intr_dyn = false); - virtual ~SensorBase(); + ~SensorBase() override; unsigned int id() const; diff --git a/include/core/sensor/sensor_diff_drive.h b/include/core/sensor/sensor_diff_drive.h index f84227fc6f35697158272b5bbe7861c95f7be2f0..8238139c3a2bf85238a9d4bacc7ac02994e987dd 100644 --- a/include/core/sensor/sensor_diff_drive.h +++ b/include/core/sensor/sensor_diff_drive.h @@ -58,7 +58,7 @@ class SensorDiffDrive : public SensorBase SensorDiffDrive(const Eigen::VectorXd& _extrinsics, ParamsSensorDiffDrivePtr _intrinsics); WOLF_SENSOR_CREATE(SensorDiffDrive, ParamsSensorDiffDrive, 3); - virtual ~SensorDiffDrive(); + ~SensorDiffDrive() override; ParamsSensorDiffDriveConstPtr getParams() const; double getRadiansPerTick() const diff --git a/include/core/sensor/sensor_odom_2d.h b/include/core/sensor/sensor_odom_2d.h index 45499f5c56fb342ed8a82b8521e6c2e156d06031..b2a989a6fe2ef55092429d38b0a75698b1627be0 100644 --- a/include/core/sensor/sensor_odom_2d.h +++ b/include/core/sensor/sensor_odom_2d.h @@ -11,7 +11,7 @@ WOLF_STRUCT_PTR_TYPEDEFS(ParamsSensorOdom2d); struct ParamsSensorOdom2d : public ParamsSensorBase { - virtual ~ParamsSensorOdom2d() = default; + ~ParamsSensorOdom2d() override = default; double k_disp_to_disp; ///< ratio of displacement variance to displacement, for odometry noise calculation double k_rot_to_rot; ///< ratio of rotation variance to rotation, for odometry noise calculation @@ -46,7 +46,7 @@ class SensorOdom2d : public SensorBase SensorOdom2d(Eigen::VectorXd _extrinsics, ParamsSensorOdom2dPtr _intrinsics); WOLF_SENSOR_CREATE(SensorOdom2d, ParamsSensorOdom2d, 3); - virtual ~SensorOdom2d(); + ~SensorOdom2d() override; /** \brief Returns displacement noise factor * diff --git a/include/core/sensor/sensor_odom_3d.h b/include/core/sensor/sensor_odom_3d.h index 3d08375b4fc30e43f07f201a5653d5e83a258381..37ec082f59543e3ad19cc2bea9370abee1e03c23 100644 --- a/include/core/sensor/sensor_odom_3d.h +++ b/include/core/sensor/sensor_odom_3d.h @@ -45,7 +45,7 @@ struct ParamsSensorOdom3d : public ParamsSensorBase + "min_disp_var: " + std::to_string(min_disp_var) + "\n" + "min_rot_var: " + std::to_string(min_rot_var) + "\n"; } - virtual ~ParamsSensorOdom3d() = default; + ~ParamsSensorOdom3d() override = default; }; WOLF_PTR_TYPEDEFS(SensorOdom3d); @@ -64,7 +64,7 @@ class SensorOdom3d : public SensorBase SensorOdom3d(const Eigen::VectorXd& _extrinsics_pq, ParamsSensorOdom3dPtr params); WOLF_SENSOR_CREATE(SensorOdom3d, ParamsSensorOdom3d, 7); - virtual ~SensorOdom3d(); + ~SensorOdom3d() override; double getDispVarToDispNoiseFactor() const; double getDispVarToRotNoiseFactor() const; diff --git a/include/core/solver/solver_manager.h b/include/core/solver/solver_manager.h index 3a5e613276c432db263cf43a484b2550ec1cfac2..9b2a665facbd1cf2590a81cb311075789b33f575 100644 --- a/include/core/solver/solver_manager.h +++ b/include/core/solver/solver_manager.h @@ -54,7 +54,7 @@ struct SolverParams: public ParamsBase // } - virtual ~SolverParams() = default; + ~SolverParams() override = default; }; /** * \brief Solver manager for WOLF diff --git a/include/core/state_block/has_state_blocks.h b/include/core/state_block/has_state_blocks.h index 9462efe7a6dd314ff2ab94cbf923ee79f5c4e21e..8880fc0a2cfb09a46712a502601a801a1f923a39 100644 --- a/include/core/state_block/has_state_blocks.h +++ b/include/core/state_block/has_state_blocks.h @@ -301,9 +301,9 @@ inline VectorXd HasStateBlocks::getStateVector(const StateStructure& _sub_struct for (const char key : structure) { const auto& sb = getStateBlock(key); - if (!sb){ - WOLF_ERROR("Stateblock key ", key, " not in the structure"); - } + + assert(sb != nullptr && "Requested StateBlock key not in the structure"); + state.segment(index,sb->getSize()) = sb->getState(); index += sb->getSize(); } diff --git a/include/core/state_block/local_parametrization_angle.h b/include/core/state_block/local_parametrization_angle.h index 4cec6ba238a51a87509d1ef507ffc2b4167d8ea2..2236c1d62e94c6223f13529d2be55d9fd60baf00 100644 --- a/include/core/state_block/local_parametrization_angle.h +++ b/include/core/state_block/local_parametrization_angle.h @@ -18,15 +18,15 @@ class LocalParametrizationAngle : public LocalParametrizationBase { public: LocalParametrizationAngle(); - virtual ~LocalParametrizationAngle(); + ~LocalParametrizationAngle() override; - virtual bool plus(Eigen::Map<const Eigen::VectorXd>& _h, Eigen::Map<const Eigen::VectorXd>& _delta, - Eigen::Map<Eigen::VectorXd>& _h_plus_delta) const; - virtual bool computeJacobian(Eigen::Map<const Eigen::VectorXd>& _h, - Eigen::Map<Eigen::MatrixRowXd>& _jacobian) const; - virtual bool minus(Eigen::Map<const Eigen::VectorXd>& _x1, + bool plus(Eigen::Map<const Eigen::VectorXd>& _h, Eigen::Map<const Eigen::VectorXd>& _delta, + Eigen::Map<Eigen::VectorXd>& _h_plus_delta) const override; + bool computeJacobian(Eigen::Map<const Eigen::VectorXd>& _h, + Eigen::Map<Eigen::MatrixRowXd>& _jacobian) const override; + bool minus(Eigen::Map<const Eigen::VectorXd>& _x1, Eigen::Map<const Eigen::VectorXd>& _x2, - Eigen::Map<Eigen::VectorXd>& _x2_minus_x1); + Eigen::Map<Eigen::VectorXd>& _x2_minus_x1) override; }; diff --git a/include/core/state_block/local_parametrization_homogeneous.h b/include/core/state_block/local_parametrization_homogeneous.h index f91bdacc6b9effab0c0da1f2cd52ff102b408006..30785bb2cae80e94117d6895657b96617b6adefb 100644 --- a/include/core/state_block/local_parametrization_homogeneous.h +++ b/include/core/state_block/local_parametrization_homogeneous.h @@ -38,15 +38,15 @@ class LocalParametrizationHomogeneous : public LocalParametrizationBase { public: LocalParametrizationHomogeneous(); - virtual ~LocalParametrizationHomogeneous(); + ~LocalParametrizationHomogeneous() override; - virtual bool plus(Eigen::Map<const Eigen::VectorXd>& _h, + bool plus(Eigen::Map<const Eigen::VectorXd>& _h, Eigen::Map<const Eigen::VectorXd>& _delta, - Eigen::Map<Eigen::VectorXd>& _h_plus_delta) const; - virtual bool computeJacobian(Eigen::Map<const Eigen::VectorXd>& _h, Eigen::Map<Eigen::MatrixRowXd>& _jacobian) const; - virtual bool minus(Eigen::Map<const Eigen::VectorXd>& _h1, + Eigen::Map<Eigen::VectorXd>& _h_plus_delta) const override; + bool computeJacobian(Eigen::Map<const Eigen::VectorXd>& _h, Eigen::Map<Eigen::MatrixRowXd>& _jacobian) const override; + bool minus(Eigen::Map<const Eigen::VectorXd>& _h1, Eigen::Map<const Eigen::VectorXd>& _h2, - Eigen::Map<Eigen::VectorXd>& _h2_minus_h1); + Eigen::Map<Eigen::VectorXd>& _h2_minus_h1) override; }; } // namespace wolf diff --git a/include/core/state_block/local_parametrization_quaternion.h b/include/core/state_block/local_parametrization_quaternion.h index 1d43ace31892c4d3a4b72be1b3a2883dd3ba787a..75804f85dabc9d9480ef045944f195fe1a472bb9 100644 --- a/include/core/state_block/local_parametrization_quaternion.h +++ b/include/core/state_block/local_parametrization_quaternion.h @@ -59,20 +59,20 @@ public: // } - virtual ~LocalParametrizationQuaternion() + ~LocalParametrizationQuaternion() override { // } - virtual bool plus(Eigen::Map<const Eigen::VectorXd>& _q, + bool plus(Eigen::Map<const Eigen::VectorXd>& _q, Eigen::Map<const Eigen::VectorXd>& _delta_theta, - Eigen::Map<Eigen::VectorXd>& _q_plus_delta_theta) const; + Eigen::Map<Eigen::VectorXd>& _q_plus_delta_theta) const override; - virtual bool computeJacobian(Eigen::Map<const Eigen::VectorXd>& _q, - Eigen::Map<Eigen::MatrixRowXd>& _jacobian) const; - virtual bool minus(Eigen::Map<const Eigen::VectorXd>& _q1, + bool computeJacobian(Eigen::Map<const Eigen::VectorXd>& _q, + Eigen::Map<Eigen::MatrixRowXd>& _jacobian) const override; + bool minus(Eigen::Map<const Eigen::VectorXd>& _q1, Eigen::Map<const Eigen::VectorXd>& _q2, - Eigen::Map<Eigen::VectorXd>& _q2_minus_q1); + Eigen::Map<Eigen::VectorXd>& _q2_minus_q1) override; }; typedef LocalParametrizationQuaternion<DQ_GLOBAL> LocalParametrizationQuaternionGlobal; diff --git a/include/core/state_block/state_angle.h b/include/core/state_block/state_angle.h index 8b714b64c8b3bd82699fab1d845887e2bd74e10c..1a5fda068c7befa1c563bcbfe05f938e0d4c576b 100644 --- a/include/core/state_block/state_angle.h +++ b/include/core/state_block/state_angle.h @@ -19,7 +19,7 @@ class StateAngle : public StateBlock public: StateAngle(double _angle = 0.0, bool _fixed = false); - virtual ~StateAngle(); + ~StateAngle() override; static StateBlockPtr create(const Eigen::VectorXd& _state, bool _fixed); }; diff --git a/include/core/state_block/state_composite.h b/include/core/state_block/state_composite.h index 44fdc98d588d46cbdf996ff94ec788f38bf7ce9c..0d3cafcc80c602a4de1bf59b9ce7c2ddd9123c9a 100644 --- a/include/core/state_block/state_composite.h +++ b/include/core/state_block/state_composite.h @@ -49,8 +49,6 @@ class VectorComposite : public std::unordered_map < std::string, Eigen::VectorXd VectorComposite(const VectorXd& _v, const StateStructure& _structure, const std::list<int>& _sizes); VectorComposite(const StateStructure& _structure, const std::list<VectorXd>& _vectors); - unsigned int size(const StateStructure& _structure) const; - Eigen::VectorXd vector(const StateStructure& _structure) const; /** diff --git a/include/core/state_block/state_homogeneous_3d.h b/include/core/state_block/state_homogeneous_3d.h index ec42d19e188593b61db2a78b8f6ecbf35680216d..ccc45424e0304ab4705e6eab9625a5d5b67ab290 100644 --- a/include/core/state_block/state_homogeneous_3d.h +++ b/include/core/state_block/state_homogeneous_3d.h @@ -18,10 +18,10 @@ class StateHomogeneous3d : public StateBlock public: StateHomogeneous3d(bool _fixed = false); StateHomogeneous3d(const Eigen::VectorXd _state, bool _fixed = false); - virtual ~StateHomogeneous3d(); + ~StateHomogeneous3d() override; - virtual void setIdentity(bool _notify = true) override; - virtual Eigen::VectorXd identity() const override; + void setIdentity(bool _notify = true) override; + Eigen::VectorXd identity() const override; static StateBlockPtr create(const Eigen::VectorXd& _state, bool _fixed); }; diff --git a/include/core/state_block/state_quaternion.h b/include/core/state_block/state_quaternion.h index 1533607134e89684674a4eec1d88d7cc83c9e6f0..d52b18c83165ac2cfe98bcebd944db4c612a4887 100644 --- a/include/core/state_block/state_quaternion.h +++ b/include/core/state_block/state_quaternion.h @@ -19,10 +19,10 @@ class StateQuaternion : public StateBlock StateQuaternion(bool _fixed = false); StateQuaternion(const Eigen::VectorXd& _state, bool _fixed = false); StateQuaternion(const Eigen::Quaterniond& _quaternion, bool _fixed = false); - virtual ~StateQuaternion(); + ~StateQuaternion() override; - virtual void setIdentity(bool _notify = true) override; - virtual Eigen::VectorXd identity() const override; + void setIdentity(bool _notify = true) override; + Eigen::VectorXd identity() const override; static StateBlockPtr create(const Eigen::VectorXd& _state, bool _fixed); }; diff --git a/include/core/trajectory/trajectory_base.h b/include/core/trajectory/trajectory_base.h index 5fe9c6c9184cbdca679f5832b910be6b1bc19f99..152a7b40e8d154f0b251d8fd322c5f0473126972 100644 --- a/include/core/trajectory/trajectory_base.h +++ b/include/core/trajectory/trajectory_base.h @@ -31,7 +31,7 @@ class TrajectoryBase : public NodeBase, public std::enable_shared_from_this<Traj public: TrajectoryBase(); - virtual ~TrajectoryBase(); + ~TrajectoryBase() override; // Frames const FrameBasePtrList& getFrameList() const; diff --git a/include/core/tree_manager/tree_manager_base.h b/include/core/tree_manager/tree_manager_base.h index 53ef9825ab029933b8c58e497e792d4f101c0406..2ffef15edf2e8a719581f76bbd957836ba6dc051 100644 --- a/include/core/tree_manager/tree_manager_base.h +++ b/include/core/tree_manager/tree_manager_base.h @@ -53,7 +53,7 @@ struct ParamsTreeManagerBase : public ParamsBase { } - virtual ~ParamsTreeManagerBase() = default; + ~ParamsTreeManagerBase() override = default; std::string print() const { @@ -69,7 +69,7 @@ class TreeManagerBase : public NodeBase params_(_params) {} - virtual ~TreeManagerBase(){} + ~TreeManagerBase() override{} virtual void keyFrameCallback(FrameBasePtr _key_frame) = 0; diff --git a/include/core/tree_manager/tree_manager_sliding_window.h b/include/core/tree_manager/tree_manager_sliding_window.h index 8b2deec3b4fe8de046e1dd6c65c646be1a773727..0ff5f31ed2734b7840518bf18dfc32073dac4cec 100644 --- a/include/core/tree_manager/tree_manager_sliding_window.h +++ b/include/core/tree_manager/tree_manager_sliding_window.h @@ -41,9 +41,9 @@ class TreeManagerSlidingWindow : public TreeManagerBase {}; WOLF_TREE_MANAGER_CREATE(TreeManagerSlidingWindow, ParamsTreeManagerSlidingWindow) - virtual ~TreeManagerSlidingWindow(){} + ~TreeManagerSlidingWindow() override{} - virtual void keyFrameCallback(FrameBasePtr _key_frame) override; + void keyFrameCallback(FrameBasePtr _key_frame) override; protected: ParamsTreeManagerSlidingWindowPtr params_sw_; diff --git a/include/core/utils/loader.h b/include/core/utils/loader.h index 6f1a4cc68c2d0dcb20a6ef18f53ec259507fc176..7da10d043ebaf5f64f28520d11fe2b114a3c1284 100644 --- a/include/core/utils/loader.h +++ b/include/core/utils/loader.h @@ -17,8 +17,8 @@ class LoaderRaw: public Loader{ public: LoaderRaw(std::string _file); ~LoaderRaw(); - void load(); - void close(); + void load() override; + void close() override; }; // class LoaderPlugin: public Loader{ // ClassLoader* resource_; diff --git a/include/core/utils/utils_gtest.h b/include/core/utils/utils_gtest.h index 53358effaeeb707c7db55dbde51568d68e5efdb6..31564f92f125ec81cbc2273e56dc032d057b6250 100644 --- a/include/core/utils/utils_gtest.h +++ b/include/core/utils/utils_gtest.h @@ -81,7 +81,7 @@ extern void ColoredPrintf(GTestColor color, const char* fmt, ...); class TestCout : public std::stringstream { public: - ~TestCout() + ~TestCout() override { PRINTF("%s\n", str().c_str()); } diff --git a/src/capture/capture_base.cpp b/src/capture/capture_base.cpp index c091b5527677fb491fb2b819de8770aae7e497c2..8b31edc53276216811daa1ca640bf042e1c4f82b 100644 --- a/src/capture/capture_base.cpp +++ b/src/capture/capture_base.cpp @@ -232,7 +232,7 @@ void CaptureBase::setProblem(ProblemPtr _problem) void CaptureBase::printHeader(int _depth, bool _constr_by, bool _metric, bool _state_blocks, std::ostream& _stream, std::string _tabs) const { - _stream << _tabs << "Cap" << id() << " " << getType(); + _stream << _tabs << "Cap" << id() << " " << getType() << " ts = " << std::setprecision(3) << getTimeStamp(); if(getSensor() != nullptr) { @@ -261,8 +261,7 @@ void CaptureBase::printHeader(int _depth, bool _constr_by, bool _metric, bool _s } else if (_metric) { - _stream << _tabs << (isFixed() ? "Fix" : "Est") << ", ts=" << std::setprecision(5) - << getTimeStamp(); + _stream << _tabs << (isFixed() ? "Fix" : "Est"); _stream << ",\t x= ( " << std::setprecision(2) << getStateVector() << " )"; _stream << std::endl; } diff --git a/src/capture/capture_motion.cpp b/src/capture/capture_motion.cpp index 1a61a7f5c763a4508427c5fb2566c3fd53248af7..4c7fd3ffbf662f887b2ceea92d00a49241758693 100644 --- a/src/capture/capture_motion.cpp +++ b/src/capture/capture_motion.cpp @@ -72,7 +72,7 @@ bool CaptureMotion::containsTimeStamp (const TimeStamp& _ts, double _time_tolera void CaptureMotion::printHeader(int _depth, bool _constr_by, bool _metric, bool _state_blocks, std::ostream& _stream, std::string _tabs) const { - _stream << _tabs << "CapM" << id() << " " << getType(); + _stream << _tabs << "CapM" << id() << " " << getType() << " ts = " << std::setprecision(3) << getTimeStamp(); if(getSensor() != nullptr) { diff --git a/src/problem/problem.cpp b/src/problem/problem.cpp index d891254c254260613da01e7072815c218f3655fe..7355c76e3856373db8c19c89c38e3fbe970a4c37 100644 --- a/src/problem/problem.cpp +++ b/src/problem/problem.cpp @@ -440,6 +440,7 @@ VectorComposite Problem::getState(const StateStructure& _structure) const state.insert(pair_key_vec); } } + // check for empty blocks and fill them with zeros for (const auto& ckey : frame_structure_) { @@ -483,6 +484,15 @@ VectorComposite Problem::getState (const TimeStamp& _ts, const StateStructure& _ state.insert(pair_key_vec); } } + + // check for empty blocks and fill them with zeros + for (const auto& ckey : frame_structure_) + { + const auto& key = string(1,ckey); + if (state.count(key) == 0) + state.emplace(key, stateZero(key).at(key)); + } + return state; } diff --git a/src/state_block/state_composite.cpp b/src/state_block/state_composite.cpp index 612b8e53ec55d7e5b787a5aa0c49312d21dfe4a9..90b7f47c6b5ffa2a28374b5673827d325224430f 100644 --- a/src/state_block/state_composite.cpp +++ b/src/state_block/state_composite.cpp @@ -62,18 +62,6 @@ VectorComposite::VectorComposite (const StateStructure& _structure, const std::l } -unsigned int VectorComposite::size(const StateStructure &_structure) const -{ - unsigned int size = 0; - for (const auto& ckey : _structure) - { - std::string key(1,ckey); // ckey is char - const VectorXd& v = this->at(key); - size += v.size(); - } - return size; -} - Eigen::VectorXd VectorComposite::vector(const StateStructure &_structure) const { // traverse once with unordered_map access diff --git a/test/dummy/factor_dummy_zero_1.h b/test/dummy/factor_dummy_zero_1.h index 1ebe1b8fe2e4eba79fe2c9fbf236da5844327189..e0d5b37f33be7abb69c853f05cb58082a1a073f0 100644 --- a/test/dummy/factor_dummy_zero_1.h +++ b/test/dummy/factor_dummy_zero_1.h @@ -28,9 +28,9 @@ class FactorDummyZero1 : public FactorAutodiff<FactorDummyZero1, 1, 1> // } - virtual ~FactorDummyZero1() = default; + ~FactorDummyZero1() override = default; - virtual std::string getTopology() const override + std::string getTopology() const override { return std::string("MOTION"); } diff --git a/test/dummy/factor_dummy_zero_12.h b/test/dummy/factor_dummy_zero_12.h index c60b9ce3232aa5c18807e80fbfb766cde275c953..fc38a80ac51826e9ab732988694867d409cbe7c7 100644 --- a/test/dummy/factor_dummy_zero_12.h +++ b/test/dummy/factor_dummy_zero_12.h @@ -50,9 +50,9 @@ class FactorDummyZero12 : public FactorAutodiff<FactorDummyZero12<ID>, ID, 1, 2, assert(id > 0 && id <= 12); } - virtual ~FactorDummyZero12() = default; + ~FactorDummyZero12() override = default; - virtual std::string getTopology() const override + std::string getTopology() const override { return std::string("MOTION"); } diff --git a/test/dummy/factor_feature_dummy.h b/test/dummy/factor_feature_dummy.h index 48c7d66ff9482ed55df9f166374948a0d07ef672..e4e8dd9de40bd5743cad60863c5b6520ad16ea15 100644 --- a/test/dummy/factor_feature_dummy.h +++ b/test/dummy/factor_feature_dummy.h @@ -16,36 +16,36 @@ class FactorFeatureDummy : public FactorBase bool _apply_loss_function = false, FactorStatus _status = FAC_ACTIVE); - virtual ~FactorFeatureDummy() = default; + ~FactorFeatureDummy() override = default; - virtual std::string getTopology() const override + std::string getTopology() const override { return "DUMMY"; } /** \brief Evaluate the factor given the input parameters and returning the residuals and jacobians **/ - virtual bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const override {return true;}; + bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const override {return true;}; /** Returns a residual vector and a vector of Jacobian matrix corresponding to each state block evaluated in the point provided in _states_ptr **/ - virtual void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const override {}; + void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const override {}; /** \brief Returns the jacobians computation method **/ - virtual JacobianMethod getJacobianMethod() const override {return JAC_ANALYTIC;} + JacobianMethod getJacobianMethod() const override {return JAC_ANALYTIC;} /** \brief Returns a vector of pointers to the states in which this factor depends **/ - virtual std::vector<StateBlockPtr> getStateBlockPtrVector() const override {return std::vector<StateBlockPtr>(0);} + std::vector<StateBlockPtr> getStateBlockPtrVector() const override {return std::vector<StateBlockPtr>(0);} /** \brief Returns the factor residual size **/ - virtual unsigned int getSize() const override {return 0;} + unsigned int getSize() const override {return 0;} /** \brief Returns the factor states sizes **/ - virtual std::vector<unsigned int> getStateSizes() const override {return std::vector<unsigned int>({1});} + std::vector<unsigned int> getStateSizes() const override {return std::vector<unsigned int>({1});} public: static FactorBasePtr create(const FeatureBasePtr& _feature_ptr, diff --git a/test/dummy/factor_landmark_dummy.h b/test/dummy/factor_landmark_dummy.h index 8adcfff4ec7891cee87da0fe0b70fd0bb15e0065..fe48f26281881be922234204032d45f271669521 100644 --- a/test/dummy/factor_landmark_dummy.h +++ b/test/dummy/factor_landmark_dummy.h @@ -16,43 +16,43 @@ class FactorLandmarkDummy : public FactorBase bool _apply_loss_function = false, FactorStatus _status = FAC_ACTIVE); - virtual ~FactorLandmarkDummy() = default; + ~FactorLandmarkDummy() override = default; - virtual std::string getTopology() const override + std::string getTopology() const override { return "DUMMY"; } /** \brief Evaluate the factor given the input parameters and returning the residuals and jacobians **/ - virtual bool evaluate(double const* const* parameters, + bool evaluate(double const* const* parameters, double* residuals, double** jacobians) const override {return true;}; /** Returns a residual vector and a vector of Jacobian matrix corresponding to each state block evaluated in the point provided in _states_ptr **/ - virtual void evaluate(const std::vector<const double*>& _states_ptr, + void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& residual_, std::vector<Eigen::MatrixXd>& jacobians_) const override {}; /** \brief Returns the jacobians computation method **/ - virtual JacobianMethod getJacobianMethod() const override {return JAC_ANALYTIC;} + JacobianMethod getJacobianMethod() const override {return JAC_ANALYTIC;} /** \brief Returns a vector of pointers to the states in which this factor depends **/ - virtual std::vector<StateBlockPtr> getStateBlockPtrVector() const override + std::vector<StateBlockPtr> getStateBlockPtrVector() const override { return std::vector<StateBlockPtr>(0); } /** \brief Returns the factor residual size **/ - virtual unsigned int getSize() const override {return 0;} + unsigned int getSize() const override {return 0;} /** \brief Returns the factor states sizes **/ - virtual std::vector<unsigned int> getStateSizes() const override + std::vector<unsigned int> getStateSizes() const override { return std::vector<unsigned int>({1}); } diff --git a/test/dummy/processor_tracker_feature_dummy.h b/test/dummy/processor_tracker_feature_dummy.h index d06ac67503acfda0a55d9418bac339359b3d9625..12705325ac8b8b086b10ec1f0a1a13870b76b702 100644 --- a/test/dummy/processor_tracker_feature_dummy.h +++ b/test/dummy/processor_tracker_feature_dummy.h @@ -39,12 +39,12 @@ class ProcessorTrackerFeatureDummy : public ProcessorTrackerFeature public: ProcessorTrackerFeatureDummy(ParamsProcessorTrackerFeatureDummyPtr _params_tracker_feature); - virtual ~ProcessorTrackerFeatureDummy(); + ~ProcessorTrackerFeatureDummy() override; // Factory method for high level API WOLF_PROCESSOR_CREATE(ProcessorTrackerFeatureDummy, ParamsProcessorTrackerFeatureDummy); - virtual void configure(SensorBasePtr _sensor) override { }; + void configure(SensorBasePtr _sensor) override { }; protected: @@ -61,7 +61,7 @@ class ProcessorTrackerFeatureDummy : public ProcessorTrackerFeature * * \return the number of features tracked */ - virtual unsigned int trackFeatures(const FeatureBasePtrList& _features_in, + unsigned int trackFeatures(const FeatureBasePtrList& _features_in, const CaptureBasePtr& _capture, FeatureBasePtrList& _features_out, FeatureMatchMap& _feature_correspondences) override; @@ -71,7 +71,7 @@ class ProcessorTrackerFeatureDummy : public ProcessorTrackerFeature * \param _incoming_feature input/output feature in incoming capture to be corrected * \return false if the the process discards the correspondence with origin's feature */ - virtual bool correctFeatureDrift(const FeatureBasePtr _origin_feature, + bool correctFeatureDrift(const FeatureBasePtr _origin_feature, const FeatureBasePtr _last_feature, FeatureBasePtr _incoming_feature) override; @@ -82,7 +82,7 @@ class ProcessorTrackerFeatureDummy : public ProcessorTrackerFeature * * WARNING! This function only votes! It does not create KeyFrames! */ - virtual bool voteForKeyFrame() const override; + bool voteForKeyFrame() const override; /** \brief Detect new Features * \param _max_features maximum number of features detected (-1: unlimited. 0: none) @@ -98,7 +98,7 @@ class ProcessorTrackerFeatureDummy : public ProcessorTrackerFeature * The function is called in ProcessorTrackerFeature::processNew() to set the member new_features_last_, * the list of newly detected features of the capture last_ptr_. */ - virtual unsigned int detectNewFeatures(const int& _max_new_features, + unsigned int detectNewFeatures(const int& _max_new_features, const CaptureBasePtr& _capture, FeatureBasePtrList& _features_out) override; /** \brief Emplaces a new factor @@ -107,7 +107,7 @@ class ProcessorTrackerFeatureDummy : public ProcessorTrackerFeature * * This function emplaces a factor of the appropriate type for the derived processor. */ - virtual FactorBasePtr emplaceFactor(FeatureBasePtr _feature_ptr, + FactorBasePtr emplaceFactor(FeatureBasePtr _feature_ptr, FeatureBasePtr _feature_other_ptr) override; }; diff --git a/test/dummy/processor_tracker_landmark_dummy.h b/test/dummy/processor_tracker_landmark_dummy.h index 5140a2b2762db740944019ac1595e7d37bf07a2c..58561c896a4764202654853cf852f7afb0cc954e 100644 --- a/test/dummy/processor_tracker_landmark_dummy.h +++ b/test/dummy/processor_tracker_landmark_dummy.h @@ -33,12 +33,12 @@ class ProcessorTrackerLandmarkDummy : public ProcessorTrackerLandmark { public: ProcessorTrackerLandmarkDummy(ParamsProcessorTrackerLandmarkDummyPtr _params_tracker_landmark_dummy); - virtual ~ProcessorTrackerLandmarkDummy(); + ~ProcessorTrackerLandmarkDummy() override; // Factory method for high level API WOLF_PROCESSOR_CREATE(ProcessorTrackerLandmarkDummy, ParamsProcessorTrackerLandmarkDummy); - virtual void configure(SensorBasePtr _sensor) override { }; + void configure(SensorBasePtr _sensor) override { }; protected: @@ -55,7 +55,7 @@ class ProcessorTrackerLandmarkDummy : public ProcessorTrackerLandmark * * \return the number of landmarks found */ - virtual unsigned int findLandmarks(const LandmarkBasePtrList& _landmarks_in, + unsigned int findLandmarks(const LandmarkBasePtrList& _landmarks_in, const CaptureBasePtr& _capture, FeatureBasePtrList& _features_out, LandmarkMatchMap& _feature_landmark_correspondences) override; @@ -67,7 +67,7 @@ class ProcessorTrackerLandmarkDummy : public ProcessorTrackerLandmark * * WARNING! This function only votes! It does not create KeyFrames! */ - virtual bool voteForKeyFrame() const override; + bool voteForKeyFrame() const override; /** \brief Detect new Features * \param _max_features maximum number of features detected (-1: unlimited. 0: none) @@ -83,7 +83,7 @@ class ProcessorTrackerLandmarkDummy : public ProcessorTrackerLandmark * The function is called in ProcessorTrackerLandmark::processNew() to set the member new_features_last_, * the list of newly detected features of the capture last_ptr_. */ - virtual unsigned int detectNewFeatures(const int& _max_new_features, + unsigned int detectNewFeatures(const int& _max_new_features, const CaptureBasePtr& _capture, FeatureBasePtrList& _features_out) override; @@ -91,7 +91,7 @@ class ProcessorTrackerLandmarkDummy : public ProcessorTrackerLandmark * * Implement in derived classes to build the type of landmark you need for this tracker. */ - virtual LandmarkBasePtr emplaceLandmark(FeatureBasePtr _feature_ptr) override; + LandmarkBasePtr emplaceLandmark(FeatureBasePtr _feature_ptr) override; /** \brief Emplace a new factor * \param _feature_ptr pointer to the Feature to constrain @@ -99,7 +99,7 @@ class ProcessorTrackerLandmarkDummy : public ProcessorTrackerLandmark * * Implement this method in derived classes. */ - virtual FactorBasePtr emplaceFactor(FeatureBasePtr _feature_ptr, + FactorBasePtr emplaceFactor(FeatureBasePtr _feature_ptr, LandmarkBasePtr _landmark_ptr) override; }; diff --git a/test/dummy/solver_manager_dummy.h b/test/dummy/solver_manager_dummy.h index fe62d065c64fbf2f4c37f58b00ff4f51ea2a0ef1..15db720a3c42f8151dd8745dc35d0232fc0fe885 100644 --- a/test/dummy/solver_manager_dummy.h +++ b/test/dummy/solver_manager_dummy.h @@ -51,10 +51,10 @@ class SolverManagerDummy : public SolverManager return state_block_local_param_.find(st) != state_block_local_param_.end(); }; - virtual void computeCovariances(const CovarianceBlocksToBeComputed blocks) override {}; - virtual void computeCovariances(const std::vector<StateBlockPtr>& st_list) override {}; - virtual bool isStateBlockRegisteredDerived(const StateBlockPtr& state_ptr) override {return true;}; - virtual bool isFactorRegisteredDerived(const FactorBasePtr& fac_ptr) const override {return true;}; + void computeCovariances(const CovarianceBlocksToBeComputed blocks) override {}; + void computeCovariances(const std::vector<StateBlockPtr>& st_list) override {}; + bool isStateBlockRegisteredDerived(const StateBlockPtr& state_ptr) override {return true;}; + bool isFactorRegisteredDerived(const FactorBasePtr& fac_ptr) const override {return true;}; // The following are dummy implementations bool hasConverged() override { return true; } @@ -66,31 +66,31 @@ class SolverManagerDummy : public SolverManager protected: - virtual bool checkDerived(std::string prefix="") const override {return true;} - virtual std::string solveDerived(const ReportVerbosity report_level) override { return std::string("");}; - virtual void addFactorDerived(const FactorBasePtr& fac_ptr) override + bool checkDerived(std::string prefix="") const override {return true;} + std::string solveDerived(const ReportVerbosity report_level) override { return std::string("");}; + void addFactorDerived(const FactorBasePtr& fac_ptr) override { factors_.push_back(fac_ptr); }; - virtual void removeFactorDerived(const FactorBasePtr& fac_ptr) override + void removeFactorDerived(const FactorBasePtr& fac_ptr) override { factors_.remove(fac_ptr); }; - virtual void addStateBlockDerived(const StateBlockPtr& state_ptr) override + void addStateBlockDerived(const StateBlockPtr& state_ptr) override { state_block_fixed_[state_ptr] = state_ptr->isFixed(); state_block_local_param_[state_ptr] = state_ptr->getLocalParametrization(); }; - virtual void removeStateBlockDerived(const StateBlockPtr& state_ptr) override + void removeStateBlockDerived(const StateBlockPtr& state_ptr) override { state_block_fixed_.erase(state_ptr); state_block_local_param_.erase(state_ptr); }; - virtual void updateStateBlockStatusDerived(const StateBlockPtr& state_ptr) override + void updateStateBlockStatusDerived(const StateBlockPtr& state_ptr) override { state_block_fixed_[state_ptr] = state_ptr->isFixed(); }; - virtual void updateStateBlockLocalParametrizationDerived(const StateBlockPtr& state_ptr) override + void updateStateBlockLocalParametrizationDerived(const StateBlockPtr& state_ptr) override { if (state_ptr->getLocalParametrization() == nullptr) state_block_local_param_.erase(state_ptr); diff --git a/test/dummy/tree_manager_dummy.h b/test/dummy/tree_manager_dummy.h index ce8e6379ece21e6a5422445b183f0576a88cc720..662c7d15677173fc302c02b10b1f660297753daf 100644 --- a/test/dummy/tree_manager_dummy.h +++ b/test/dummy/tree_manager_dummy.h @@ -16,7 +16,7 @@ struct ParamsTreeManagerDummy : public ParamsTreeManagerBase toy_param = _server.getParam<double>(prefix + "/toy_param"); } - virtual ~ParamsTreeManagerDummy() = default; + ~ParamsTreeManagerDummy() override = default; bool toy_param; @@ -38,9 +38,9 @@ class TreeManagerDummy : public TreeManagerBase {}; WOLF_TREE_MANAGER_CREATE(TreeManagerDummy, ParamsTreeManagerBase) - virtual ~TreeManagerDummy(){} + ~TreeManagerDummy() override{} - virtual void keyFrameCallback(FrameBasePtr _KF) override + void keyFrameCallback(FrameBasePtr _KF) override { n_KF_++; }; diff --git a/test/gtest_ceres_manager.cpp b/test/gtest_ceres_manager.cpp index d2b5c7e01b70fa65472f3e18bbfa7b38d8989679..454ff6dfb13d7db63818eafebc10ebec6630cf66 100644 --- a/test/gtest_ceres_manager.cpp +++ b/test/gtest_ceres_manager.cpp @@ -60,7 +60,7 @@ class CeresManagerWrapper : public CeresManager return ceres_problem_->NumResidualBlocks(); }; - bool isFactorRegistered(const FactorBasePtr& fac_ptr) const + bool isFactorRegistered(const FactorBasePtr& fac_ptr) const override { return fac_2_residual_idx_.find(fac_ptr) != fac_2_residual_idx_.end() && fac_2_costfunction_.find(fac_ptr) != fac_2_costfunction_.end(); }; diff --git a/test/gtest_factor_autodiff_distance_3d.cpp b/test/gtest_factor_autodiff_distance_3d.cpp index e25e1505a3ddaa15ecfa6152fc007bc6009696f9..57235013f2c82a115a4fcafd389ac8421195651e 100644 --- a/test/gtest_factor_autodiff_distance_3d.cpp +++ b/test/gtest_factor_autodiff_distance_3d.cpp @@ -36,7 +36,7 @@ class FactorAutodiffDistance3d_Test : public testing::Test ProblemPtr problem; CeresManagerPtr ceres_manager; - void SetUp() + void SetUp() override { pos1 << 1, 0, 0; pos2 << 0, 1, 0; diff --git a/test/gtest_factor_base.cpp b/test/gtest_factor_base.cpp index 3237da062337d5a26c3c320e63df62c7d2798fb8..05c9f8c7980df3bb47aeb80a0b28408302ba0b4c 100644 --- a/test/gtest_factor_base.cpp +++ b/test/gtest_factor_base.cpp @@ -22,7 +22,7 @@ class FactorBaseTest : public testing::Test FeatureBasePtr f0,f1; LandmarkBasePtr L0,L1; - virtual void SetUp() + void SetUp() override { F0 = std::make_shared<FrameBase>(KEY, 0.0, nullptr); F1 = std::make_shared<FrameBase>(KEY, 1.0, nullptr); @@ -71,19 +71,19 @@ class FactorDummy : public FactorBase { // } - virtual ~FactorDummy() = default; + ~FactorDummy() override = default; - virtual std::string getTopology() const override {return "DUMMY";} - virtual bool evaluate(double const* const* _parameters, + std::string getTopology() const override {return "DUMMY";} + bool evaluate(double const* const* _parameters, double* _residuals, double** _jacobians) const override {return true;} - virtual void evaluate(const std::vector<const double*>& _states_ptr, + void evaluate(const std::vector<const double*>& _states_ptr, Eigen::VectorXd& _residual, std::vector<Eigen::MatrixXd>& _jacobians) const override {} - virtual JacobianMethod getJacobianMethod() const override {return JacobianMethod::JAC_ANALYTIC;} - virtual std::vector<StateBlockPtr> getStateBlockPtrVector() const override {std::vector<StateBlockPtr> v; return v;} - virtual std::vector<unsigned int> getStateSizes() const override {std::vector<unsigned int> v; return v;} - virtual unsigned int getSize() const override {return 0;} + JacobianMethod getJacobianMethod() const override {return JacobianMethod::JAC_ANALYTIC;} + std::vector<StateBlockPtr> getStateBlockPtrVector() const override {std::vector<StateBlockPtr> v; return v;} + std::vector<unsigned int> getStateSizes() const override {std::vector<unsigned int> v; return v;} + unsigned int getSize() const override {return 0;} }; diff --git a/test/gtest_factor_block_difference.cpp b/test/gtest_factor_block_difference.cpp index bee51d78e417f1f446a5890fa1ead4834dc366bc..9c739965701b6236dcff93fbafba1bd12f90eddb 100644 --- a/test/gtest_factor_block_difference.cpp +++ b/test/gtest_factor_block_difference.cpp @@ -39,7 +39,7 @@ class FixtureFactorBlockDifference : public testing::Test protected: - virtual void SetUp() override + void SetUp() override { // Problem and solver problem_ = Problem::create("POV", 3); @@ -64,7 +64,7 @@ class FixtureFactorBlockDifference : public testing::Test Cap_ = CaptureBase::emplace<CaptureBase>(KF1_, "BlockDifference", t1); } - virtual void TearDown() override {} + void TearDown() override {} }; TEST_F(FixtureFactorBlockDifference, CheckFactorType) diff --git a/test/gtest_factor_diff_drive.cpp b/test/gtest_factor_diff_drive.cpp index 0413c21cb2c30bb91b1a03dabac0b595d1843349..713fd1c1b26624b84612a1e721eb4924db08777c 100644 --- a/test/gtest_factor_diff_drive.cpp +++ b/test/gtest_factor_diff_drive.cpp @@ -30,68 +30,68 @@ class ProcessorDiffDrivePublic : public ProcessorDiffDrive { // } - virtual void configure(SensorBasePtr _sensor) + void configure(SensorBasePtr _sensor) override { Base::configure(_sensor); } - virtual void computeCurrentDelta(const Eigen::VectorXd& _data, + void computeCurrentDelta(const Eigen::VectorXd& _data, const Eigen::MatrixXd& _data_cov, const Eigen::VectorXd& _calib, const double _dt, Eigen::VectorXd& _delta, Eigen::MatrixXd& _delta_cov, - Eigen::MatrixXd& _jacobian_calib) const + Eigen::MatrixXd& _jacobian_calib) const override { Base::computeCurrentDelta(_data, _data_cov, _calib, _dt, _delta, _delta_cov, _jacobian_calib); } - virtual void deltaPlusDelta(const Eigen::VectorXd& _delta1, + void deltaPlusDelta(const Eigen::VectorXd& _delta1, const Eigen::VectorXd& _delta2, const double _dt2, - Eigen::VectorXd& _delta1_plus_delta2) const + Eigen::VectorXd& _delta1_plus_delta2) const override { Base::deltaPlusDelta(_delta1, _delta2, _dt2, _delta1_plus_delta2); } - virtual void deltaPlusDelta(const Eigen::VectorXd& _delta1, + void deltaPlusDelta(const Eigen::VectorXd& _delta1, const Eigen::VectorXd& _delta2, const double _dt2, Eigen::VectorXd& _delta1_plus_delta2, Eigen::MatrixXd& _jacobian1, - Eigen::MatrixXd& _jacobian2) const + Eigen::MatrixXd& _jacobian2) const override { Base::deltaPlusDelta(_delta1, _delta2, _dt2, _delta1_plus_delta2, _jacobian1, _jacobian2); } - virtual VectorXd getCalibration (const CaptureBasePtr _capture) const + VectorXd getCalibration (const CaptureBasePtr _capture) const override { return Base::getCalibration(_capture); } - virtual Eigen::VectorXd deltaZero() const + Eigen::VectorXd deltaZero() const override { return Base::deltaZero(); } - virtual CaptureMotionPtr emplaceCapture(const FrameBasePtr& _frame_own, + CaptureMotionPtr emplaceCapture(const FrameBasePtr& _frame_own, const SensorBasePtr& _sensor, const TimeStamp& _ts, const VectorXd& _data, const MatrixXd& _data_cov, const VectorXd& _calib, const VectorXd& _calib_preint, - const CaptureBasePtr& _capture_origin) + const CaptureBasePtr& _capture_origin) override { return Base::emplaceCapture(_frame_own, _sensor, _ts, _data, _data_cov, _calib, _calib_preint, _capture_origin); } - virtual FeatureBasePtr emplaceFeature(CaptureMotionPtr _capture_own) + FeatureBasePtr emplaceFeature(CaptureMotionPtr _capture_own) override { return Base::emplaceFeature(_capture_own); } - virtual FactorBasePtr emplaceFactor(FeatureBasePtr _feature_motion, - CaptureBasePtr _capture_origin) + FactorBasePtr emplaceFactor(FeatureBasePtr _feature_motion, + CaptureBasePtr _capture_origin) override { return Base::emplaceFactor(_feature_motion, _capture_origin); } @@ -132,7 +132,7 @@ class FactorDiffDriveTest : public testing::Test Vector3d calib; Vector3d residual; - virtual void SetUp() + void SetUp() override { problem = Problem::create("PO", 2); trajectory = problem->getTrajectory(); @@ -206,7 +206,7 @@ class FactorDiffDriveTest : public testing::Test startup_config_for_all_tests(); } - virtual void TearDown() + void TearDown() override { } diff --git a/test/gtest_has_state_blocks.cpp b/test/gtest_has_state_blocks.cpp index 111ccd08d5653eab1bb73a71a9711dc426a2ab08..4e3d610109e92b8fe6846b93050bc64af29a6f72 100644 --- a/test/gtest_has_state_blocks.cpp +++ b/test/gtest_has_state_blocks.cpp @@ -30,7 +30,7 @@ class HasStateBlocksTest : public testing::Test StateQuaternionPtr sbo0, sbo1; - virtual void SetUp() + void SetUp() override { problem = Problem::create("POV", 3); @@ -45,7 +45,7 @@ class HasStateBlocksTest : public testing::Test F1 = std::make_shared<FrameBase>(NON_ESTIMATED, 1.0, nullptr); // non KF } - virtual void TearDown(){} + void TearDown() override{} }; diff --git a/test/gtest_pack_KF_buffer.cpp b/test/gtest_pack_KF_buffer.cpp index 32bcd10d01a3604d16548cfd738d555af6b7e019..056fbcf0bb231962e109ea60f404a5a0cefd58f5 100644 --- a/test/gtest_pack_KF_buffer.cpp +++ b/test/gtest_pack_KF_buffer.cpp @@ -32,7 +32,7 @@ class BufferPackKeyFrameTest : public testing::Test TimeStamp timestamp; double timetolerance; - void SetUp(void) + void SetUp(void) override { f10 = std::make_shared<FrameBase>(NON_ESTIMATED, TimeStamp(10),nullptr,nullptr,nullptr); f20 = std::make_shared<FrameBase>(NON_ESTIMATED, TimeStamp(20),nullptr,nullptr,nullptr); diff --git a/test/gtest_processor_diff_drive.cpp b/test/gtest_processor_diff_drive.cpp index ee908013b9eadd216363d528d7f60757ea331f29..b13061e657badbd2ed81e9ea82b0f6078f3803f0 100644 --- a/test/gtest_processor_diff_drive.cpp +++ b/test/gtest_processor_diff_drive.cpp @@ -25,71 +25,71 @@ class ProcessorDiffDrivePublic : public ProcessorDiffDrive { // } - virtual void configure(SensorBasePtr _sensor) + void configure(SensorBasePtr _sensor) override { Base::configure(_sensor); } - virtual void computeCurrentDelta(const Eigen::VectorXd& _data, + void computeCurrentDelta(const Eigen::VectorXd& _data, const Eigen::MatrixXd& _data_cov, const Eigen::VectorXd& _calib, const double _dt, Eigen::VectorXd& _delta, Eigen::MatrixXd& _delta_cov, - Eigen::MatrixXd& _jacobian_calib) const + Eigen::MatrixXd& _jacobian_calib) const override { Base::computeCurrentDelta(_data, _data_cov, _calib, _dt, _delta, _delta_cov, _jacobian_calib); } - virtual void deltaPlusDelta(const Eigen::VectorXd& _delta1, + void deltaPlusDelta(const Eigen::VectorXd& _delta1, const Eigen::VectorXd& _delta2, const double _dt2, - Eigen::VectorXd& _delta1_plus_delta2) const + Eigen::VectorXd& _delta1_plus_delta2) const override { Base::deltaPlusDelta(_delta1, _delta2, _dt2, _delta1_plus_delta2); } - virtual void deltaPlusDelta(const Eigen::VectorXd& _delta1, + void deltaPlusDelta(const Eigen::VectorXd& _delta1, const Eigen::VectorXd& _delta2, const double _dt2, Eigen::VectorXd& _delta1_plus_delta2, Eigen::MatrixXd& _jacobian1, - Eigen::MatrixXd& _jacobian2) const + Eigen::MatrixXd& _jacobian2) const override { Base::deltaPlusDelta(_delta1, _delta2, _dt2, _delta1_plus_delta2, _jacobian1, _jacobian2); } - virtual void statePlusDelta(const VectorComposite& _x, + void statePlusDelta(const VectorComposite& _x, const Eigen::VectorXd& _delta, const double _dt, - VectorComposite& _x_plus_delta) const + VectorComposite& _x_plus_delta) const override { Base::statePlusDelta(_x, _delta, _dt, _x_plus_delta); } - virtual Eigen::VectorXd deltaZero() const + Eigen::VectorXd deltaZero() const override { return Base::deltaZero(); } - virtual CaptureMotionPtr emplaceCapture(const FrameBasePtr& _frame_own, + CaptureMotionPtr emplaceCapture(const FrameBasePtr& _frame_own, const SensorBasePtr& _sensor, const TimeStamp& _ts, const VectorXd& _data, const MatrixXd& _data_cov, const VectorXd& _calib, const VectorXd& _calib_preint, - const CaptureBasePtr& _capture_origin) + const CaptureBasePtr& _capture_origin) override { return Base::emplaceCapture(_frame_own, _sensor, _ts, _data, _data_cov, _calib, _calib_preint, _capture_origin); } - virtual FeatureBasePtr emplaceFeature(CaptureMotionPtr _capture_own) + FeatureBasePtr emplaceFeature(CaptureMotionPtr _capture_own) override { return Base::emplaceFeature(_capture_own); } - virtual FactorBasePtr emplaceFactor(FeatureBasePtr _feature_motion, - CaptureBasePtr _capture_origin) + FactorBasePtr emplaceFactor(FeatureBasePtr _feature_motion, + CaptureBasePtr _capture_origin) override { return Base::emplaceFactor(_feature_motion, _capture_origin); } @@ -115,7 +115,7 @@ class ProcessorDiffDriveTest : public testing::Test ProcessorDiffDrivePublicPtr processor; ProblemPtr problem; - virtual void SetUp() + void SetUp() override { problem = Problem::create("PO", 2); @@ -139,7 +139,7 @@ class ProcessorDiffDriveTest : public testing::Test processor = std::static_pointer_cast<ProcessorDiffDrivePublic>(problem->installProcessor("ProcessorDiffDrive", "processor diff drive", sensor, params)); } - virtual void TearDown(){} + void TearDown() override{} }; diff --git a/test/gtest_processor_loopclosure.cpp b/test/gtest_processor_loopclosure.cpp index 9b8683f8b74ee566370d4630a248d039257ebb17..90d55137f88921c61c2e79bee1ea19d0f9047111 100644 --- a/test/gtest_processor_loopclosure.cpp +++ b/test/gtest_processor_loopclosure.cpp @@ -29,10 +29,10 @@ public: std::pair<FrameBasePtr,CaptureBasePtr> public_selectPairKC(){ return selectPairKC();}; protected: - virtual bool voteComputeFeatures() override { return true;}; - virtual bool voteSearchLoopClosure() override { return true;}; - virtual bool detectFeatures(CaptureBasePtr cap) override { return true;}; - virtual CaptureBasePtr findLoopCandidate(CaptureBasePtr _capture) override + bool voteComputeFeatures() override { return true;}; + bool voteSearchLoopClosure() override { return true;}; + bool detectFeatures(CaptureBasePtr cap) override { return true;}; + CaptureBasePtr findLoopCandidate(CaptureBasePtr _capture) override { for (FrameBasePtr kf : getProblem()->getTrajectory()->getFrameList()) if (kf->isKey()) @@ -41,7 +41,7 @@ protected: return cap; return nullptr; }; - virtual void emplaceFactors(CaptureBasePtr _capture_1, CaptureBasePtr _capture_2) override + void emplaceFactors(CaptureBasePtr _capture_1, CaptureBasePtr _capture_2) override { std::cout << "factor created\n"; *factor_created = true; diff --git a/test/gtest_processor_motion.cpp b/test/gtest_processor_motion.cpp index 509f495c1bd4c56be08f2d70279e6fba9a5b6ccc..509c20d6ee2f9b809f4067ed03128ef7bca059a9 100644 --- a/test/gtest_processor_motion.cpp +++ b/test/gtest_processor_motion.cpp @@ -25,7 +25,7 @@ class ProcessorOdom2dPublic : public ProcessorOdom2d { // } - virtual ~ProcessorOdom2dPublic(){} + ~ProcessorOdom2dPublic() override{} void splitBuffer(const wolf::CaptureMotionPtr& capture_source, TimeStamp ts_split, @@ -56,7 +56,7 @@ class ProcessorMotion_test : public testing::Test{ // dt(0) // { } - virtual void SetUp() + void SetUp() override { std::string wolf_root = _WOLF_ROOT_DIR; @@ -74,7 +74,7 @@ class ProcessorMotion_test : public testing::Test{ capture = std::make_shared<CaptureMotion>("CaptureOdom2d", 0.0, sensor, data, data_cov, nullptr); } - virtual void TearDown(){} + void TearDown() override{} }; diff --git a/test/gtest_processor_tracker_feature_dummy.cpp b/test/gtest_processor_tracker_feature_dummy.cpp index 604cd09b4f20ed68e1c44273f85a93c8c1a88c1a..6238a5786533fc89df682364305db55661921e92 100644 --- a/test/gtest_processor_tracker_feature_dummy.cpp +++ b/test/gtest_processor_tracker_feature_dummy.cpp @@ -74,9 +74,9 @@ class ProcessorTrackerFeatureDummyTest : public testing::Test ParamsProcessorTrackerFeatureDummyPtr params; ProcessorTrackerFeatureDummyDummyPtr processor; - virtual ~ProcessorTrackerFeatureDummyTest(){} + ~ProcessorTrackerFeatureDummyTest() override{} - virtual void SetUp() + void SetUp() override { // Wolf problem problem = Problem::create("PO", 2); diff --git a/test/gtest_processor_tracker_landmark_dummy.cpp b/test/gtest_processor_tracker_landmark_dummy.cpp index 8963211c45c292341d3754e83579f8bf9738a752..44dfbdf14cc1f53ea4962cc7f2517d37ef5210b2 100644 --- a/test/gtest_processor_tracker_landmark_dummy.cpp +++ b/test/gtest_processor_tracker_landmark_dummy.cpp @@ -92,9 +92,9 @@ class ProcessorTrackerLandmarkDummyTest : public testing::Test ParamsProcessorTrackerLandmarkDummyPtr params; ProcessorTrackerLandmarkDummyDummyPtr processor; - virtual ~ProcessorTrackerLandmarkDummyTest(){} + ~ProcessorTrackerLandmarkDummyTest() override{} - virtual void SetUp() + void SetUp() override { // Wolf problem problem = Problem::create("PO", 2); diff --git a/test/gtest_shared_from_this.cpp b/test/gtest_shared_from_this.cpp index b2d5217f4be5f08525da8042478b32c871a7afa8..9506f844b32ddcf5d986d4a8067d77ad23030f71 100644 --- a/test/gtest_shared_from_this.cpp +++ b/test/gtest_shared_from_this.cpp @@ -13,7 +13,7 @@ class CParentBase : public wolf::NodeBase NodeBase("") {}; - virtual ~CParentBase(){}; + ~CParentBase() override{}; virtual void addChild(std::shared_ptr<CChildBase> _child_ptr) final { diff --git a/test/gtest_state_composite.cpp b/test/gtest_state_composite.cpp index 4d5a420119526c2fc1984aecfc22e01b40d0084b..56f705aa3b9c3689a076989fcd8e30896d80fe13 100644 --- a/test/gtest_state_composite.cpp +++ b/test/gtest_state_composite.cpp @@ -331,20 +331,6 @@ TEST(VectorComposite, unary_Minus) ASSERT_MATRIX_APPROX((-x).at("O"), Vector3d(-2,-2,-2), 1e-20); } -TEST(VectorComposite, size) -{ - VectorComposite x; - - x.emplace("P", Vector2d(1,1)); - x.emplace("O", Vector3d(2,2,2)); - x.emplace("V", Vector4d(3,3,3,3)); - - ASSERT_EQ(x.size("PO"), 5); - ASSERT_EQ(x.size("VO"), 7); - ASSERT_EQ(x.size("PVO"), 9); - ASSERT_EQ(x.size("OPV"), 9); -} - TEST(VectorComposite, stateVector) { VectorComposite x; diff --git a/test/gtest_track_matrix.cpp b/test/gtest_track_matrix.cpp index 5b333f26c6cb097957a6963e0602314ba3eef481..4e539e24b7554a7a2e5cfe88096cc4c861de4018 100644 --- a/test/gtest_track_matrix.cpp +++ b/test/gtest_track_matrix.cpp @@ -23,7 +23,7 @@ class TrackMatrixTest : public testing::Test CaptureBasePtr C0, C1, C2, C3, C4; FeatureBasePtr f0, f1, f2, f3, f4; - virtual void SetUp() + void SetUp() override { // unlinked captures // Some warnings will be thrown "linking with nullptr" for emplacing without providing frame pointer