diff --git a/demos/demo_wolf_imported_graph.cpp b/demos/demo_wolf_imported_graph.cpp index c0afa76e96229181122659244a20fd1fab433354..386d803138f33b89bee401aceda047fe2199f104 100644 --- a/demos/demo_wolf_imported_graph.cpp +++ b/demos/demo_wolf_imported_graph.cpp @@ -130,8 +130,8 @@ int main(int argc, char** argv) bNum.clear(); // add frame to problem - FrameBasePtr vertex_frame_ptr_full = new FrameBase(KEY, TimeStamp(0), std::make_shared<StateBlock>(vertex_pose.head(2)), std::make_shared<StateBlock>(vertex_pose.tail(1))); - FrameBasePtr vertex_frame_ptr_prun = new FrameBase(KEY, TimeStamp(0), std::make_shared<StateBlock>(vertex_pose.head(2)), std::make_shared<StateBlock>(vertex_pose.tail(1))); + FrameBasePtr vertex_frame_ptr_full = new FrameBase(TimeStamp(0), std::make_shared<StateBlock>(vertex_pose.head(2)), std::make_shared<StateBlock>(vertex_pose.tail(1))); + FrameBasePtr vertex_frame_ptr_prun = new FrameBase(TimeStamp(0), std::make_shared<StateBlock>(vertex_pose.head(2)), std::make_shared<StateBlock>(vertex_pose.tail(1))); wolf_problem_full->getTrajectory()->addFrame(vertex_frame_ptr_full); wolf_problem_prun->getTrajectory()->addFrame(vertex_frame_ptr_prun); // store diff --git a/demos/hello_wolf/hello_wolf.cpp b/demos/hello_wolf/hello_wolf.cpp index ef4f173494fbb602b2042088b065f45bf28ae43b..2b2d03d43f1a7d315efb0ae07a734ec022f9e4c6 100644 --- a/demos/hello_wolf/hello_wolf.cpp +++ b/demos/hello_wolf/hello_wolf.cpp @@ -233,12 +233,11 @@ int main() WOLF_TRACE("======== COVARIANCES OF SOLVED PROBLEM =======") ceres->computeCovariances(SolverManager::CovarianceBlocksToBeComputed::ALL_MARGINALS); for (auto& kf : *problem->getTrajectory()) - if (kf->isKey()) - { - Eigen::MatrixXd cov; - kf->getCovariance(cov); - WOLF_TRACE("KF", kf->id(), "_cov = \n", cov); - } + { + Eigen::MatrixXd cov; + kf->getCovariance(cov); + WOLF_TRACE("KF", kf->id(), "_cov = \n", cov); + } for (auto& lmk : problem->getMap()->getLandmarkList()) { Eigen::MatrixXd cov; diff --git a/demos/hello_wolf/hello_wolf_autoconf.cpp b/demos/hello_wolf/hello_wolf_autoconf.cpp index e975bb30fa55bb3cb39026a4377f7f4e62b2e58b..edeb6b1f04f1f673ad3af9b94493b4e67e46ab9f 100644 --- a/demos/hello_wolf/hello_wolf_autoconf.cpp +++ b/demos/hello_wolf/hello_wolf_autoconf.cpp @@ -219,12 +219,11 @@ int main() WOLF_TRACE("======== COVARIANCES OF SOLVED PROBLEM =======") ceres->computeCovariances(SolverManager::CovarianceBlocksToBeComputed::ALL_MARGINALS); for (auto& kf : *problem->getTrajectory()) - if (kf->isKey()) - { - Eigen::MatrixXd cov; - kf->getCovariance(cov); - WOLF_TRACE("KF", kf->id(), "_cov = \n", cov); - } + { + Eigen::MatrixXd cov; + kf->getCovariance(cov); + WOLF_TRACE("KF", kf->id(), "_cov = \n", cov); + } for (auto& lmk : problem->getMap()->getLandmarkList()) { Eigen::MatrixXd cov; diff --git a/include/core/capture/capture_base.h b/include/core/capture/capture_base.h index 40d3603da035205b145df7d1b7d43541a52b6a44..18a09ac3e24f36c3cef6b11c87dfc861e17d14be 100644 --- a/include/core/capture/capture_base.h +++ b/include/core/capture/capture_base.h @@ -82,7 +82,6 @@ class CaptureBase : public NodeBase, public HasStateBlocks, public std::enable_s // State blocks - const StateStructure& getStructure() const; StateBlockPtr getStateBlock(const char& _key) const; StateBlockPtr getSensorP() const; StateBlockPtr getSensorO() const; diff --git a/include/core/frame/frame_base.h b/include/core/frame/frame_base.h index 1b368bf02df6a89567d90455edba72cf02f54bf0..c4e423947d5ce6c1c00d2f70f6c510dea38e1608 100644 --- a/include/core/frame/frame_base.h +++ b/include/core/frame/frame_base.h @@ -8,15 +8,6 @@ namespace wolf{ class TrajectoryBase; class CaptureBase; class StateBlock; - -/** \brief Enumeration of frame types - */ -typedef enum -{ - KEY = 1, ///< key frame. It plays at optimizations (estimated). - // AUXILIARY = 1, ///< auxiliary frame. It plays at optimizations (estimated). - NON_ESTIMATED = 0 ///< regular frame. It does not play at optimization. -} FrameType; } //Wolf includes @@ -45,7 +36,6 @@ class FrameBase : public NodeBase, public HasStateBlocks, public std::enable_sha protected: unsigned int frame_id_; - FrameType type_; ///< type of frame. Either NON_KEY_FRAME or KEY_FRAME. (types defined at wolf.h) TimeStamp time_stamp_; ///< frame time stamp public: @@ -58,36 +48,34 @@ class FrameBase : public NodeBase, public HasStateBlocks, public std::enable_sha * \param _o_ptr StateBlock pointer to the orientation (default: nullptr) * \param _v_ptr StateBlock pointer to the velocity (default: nullptr). **/ - FrameBase(const FrameType & _tp, - const TimeStamp& _ts, + FrameBase(const TimeStamp& _ts, StateBlockPtr _p_ptr, StateBlockPtr _o_ptr = nullptr, StateBlockPtr _v_ptr = nullptr); - FrameBase(const FrameType & _tp, - const TimeStamp& _ts, + FrameBase(const TimeStamp& _ts, const std::string _frame_structure, const VectorComposite& _state); - FrameBase(const FrameType & _tp, - const TimeStamp& _ts, + FrameBase(const TimeStamp& _ts, const std::string _frame_structure, const std::list<VectorXd>& _vectors); ~FrameBase() override; + + // Add and remove from WOLF tree --------------------------------- + template<typename classType, typename... T> + static std::shared_ptr<classType> emplace(TrajectoryBasePtr _ptr, T&&... all); + + void link(TrajectoryBasePtr); + void link(ProblemPtr _prb); + virtual void remove(bool viral_remove_empty_parent=false); // Frame properties ----------------------------------------------- public: unsigned int id() const; - // get type - bool isKey() const; - - // set type - void setNonEstimated(); - void setKey(ProblemPtr _prb); - // Frame values ------------------------------------------------ public: void setTimeStamp(const TimeStamp& _ts); @@ -122,17 +110,14 @@ class FrameBase : public NodeBase, public HasStateBlocks, public std::enable_sha FactorBasePtr getFactorOf(const ProcessorBasePtr _processor_ptr) const; FactorBasePtr getFactorOf(const ProcessorBasePtr _processor_ptr, const std::string& type) const; - void getFactorList(FactorBasePtrList& _fac_list) const; + unsigned int getHits() const; const FactorBasePtrList& getConstrainedByList() const; bool isConstrainedBy(const FactorBasePtr& _factor) const; - void link(TrajectoryBasePtr); - template<typename classType, typename... T> - static std::shared_ptr<classType> emplaceKeyFrame(TrajectoryBasePtr _ptr, T&&... all); - template<typename classType, typename... T> - static std::shared_ptr<classType> createNonKeyFrame(T&&... all); + + // Debug and info ------------------------------------------------------- virtual void printHeader(int depth, // bool constr_by, // bool metric, // @@ -172,29 +157,23 @@ class FrameBase : public NodeBase, public HasStateBlocks, public std::enable_sha namespace wolf { template<typename classType, typename... T> -std::shared_ptr<classType> FrameBase::emplaceKeyFrame(TrajectoryBasePtr _ptr, T&&... all) +std::shared_ptr<classType> FrameBase::emplace(TrajectoryBasePtr _ptr, T&&... all) { - std::shared_ptr<classType> frm = std::make_shared<classType>(FrameType::KEY, std::forward<T>(all)...); + std::shared_ptr<classType> frm = std::make_shared<classType>(std::forward<T>(all)...); frm->link(_ptr); return frm; } -template<typename classType, typename... T> -std::shared_ptr<classType> FrameBase::createNonKeyFrame(T&&... all) -{ - std::shared_ptr<classType> frm = std::make_shared<classType>(FrameType::NON_ESTIMATED, std::forward<T>(all)...); - return frm; -} - inline unsigned int FrameBase::id() const { return frame_id_; } -inline bool FrameBase::isKey() const -{ - return (type_ == KEY); -} +//inline bool FrameBase::isKey() const +//{ +// return true; +//// return (type_ == KEY); +//} inline void FrameBase::getTimeStamp(TimeStamp& _ts) const { @@ -234,10 +213,7 @@ inline const FactorBasePtrList& FrameBase::getConstrainedByList() const inline StateBlockPtr FrameBase::addStateBlock(const char& _sb_type, const StateBlockPtr& _sb) { - if (isKey()) - HasStateBlocks::addStateBlock(_sb_type, _sb, getProblem()); - else - HasStateBlocks::addStateBlock(_sb_type, _sb, nullptr); + HasStateBlocks::addStateBlock(_sb_type, _sb, getProblem()); return _sb; } diff --git a/include/core/problem/problem.h b/include/core/problem/problem.h index 002015f83efac35a081aa24873f9c684cb1b36b7..44e2fe69ed430b624e3df31dfa730341b496fe90 100644 --- a/include/core/problem/problem.h +++ b/include/core/problem/problem.h @@ -206,7 +206,7 @@ class Problem : public std::enable_shared_from_this<Problem> const double &_time_tol); /** \brief Emplace frame from string frame_structure, dimension and vector - * \param _frame_key_type Either KEY, AUXILIARY or NON_ESTIMATED + * \param _frame_key_type Either AUXILIARY or NON_ESTIMATED * \param _time_stamp Time stamp of the frame * \param _frame_structure String indicating the frame structure. * \param _dim variable indicating the dimension of the problem @@ -217,13 +217,13 @@ class Problem : public std::enable_shared_from_this<Problem> * - Add it to Trajectory * - If it is key-frame, update state-block lists in Problem */ - FrameBasePtr emplaceKeyFrame(const TimeStamp& _time_stamp, // + FrameBasePtr emplaceFrame(const TimeStamp& _time_stamp, // const StateStructure& _frame_structure, // const SizeEigen _dim, // const Eigen::VectorXd& _frame_state); /** \brief Emplace frame from string frame_structure and state - * \param _frame_key_type Either KEY, AUXILIARY or NON_ESTIMATED + * \param _frame_key_type Either AUXILIARY or NON_ESTIMATED * \param _time_stamp Time stamp of the frame * \param _frame_structure String indicating the frame structure. * \param _frame_state State vector; must match the size and format of the chosen frame structure @@ -235,12 +235,12 @@ class Problem : public std::enable_shared_from_this<Problem> * - Add it to Trajectory * - If it is key-frame, update state-block lists in Problem */ - FrameBasePtr emplaceKeyFrame(const TimeStamp& _time_stamp, // + FrameBasePtr emplaceFrame(const TimeStamp& _time_stamp, // const StateStructure& _frame_structure, // const VectorComposite& _frame_state); /** \brief Emplace frame from state - * \param _frame_key_type Either KEY, AUXILIARY or NON_ESTIMATED + * \param _frame_key_type Either AUXILIARY or NON_ESTIMATED * \param _time_stamp Time stamp of the frame * \param _frame_state State; must be part of the problem's frame structure * @@ -252,11 +252,11 @@ class Problem : public std::enable_shared_from_this<Problem> * - Add it to Trajectory * - If it is key-frame, update state-block lists in Problem */ - FrameBasePtr emplaceKeyFrame(const TimeStamp& _time_stamp, // + FrameBasePtr emplaceFrame(const TimeStamp& _time_stamp, // const VectorComposite& _frame_state); /** \brief Emplace frame from string frame_structure and dimension - * \param _frame_key_type Either KEY, AUXILIARY or NON_ESTIMATED + * \param _frame_key_type Either AUXILIARY or NON_ESTIMATED * \param _time_stamp Time stamp of the frame * \param _frame_structure String indicating the frame structure. * \param _dim variable indicating the dimension of the problem @@ -269,12 +269,12 @@ class Problem : public std::enable_shared_from_this<Problem> * - Add it to Trajectory * - If it is key-frame, update state-block lists in Problem */ - FrameBasePtr emplaceKeyFrame(const TimeStamp& _time_stamp, // + FrameBasePtr emplaceFrame(const TimeStamp& _time_stamp, // const StateStructure& _frame_structure, // const SizeEigen _dim); /** \brief Emplace frame from state vector - * \param _frame_key_type Either KEY, AUXILIARY or NON_ESTIMATED + * \param _frame_key_type Either AUXILIARY or NON_ESTIMATED * \param _time_stamp Time stamp of the frame * \param _frame_state State vector; must match the size and format of the chosen frame structure * @@ -286,11 +286,11 @@ class Problem : public std::enable_shared_from_this<Problem> * - Add it to Trajectory * - If it is key-frame, update state-block lists in Problem */ - FrameBasePtr emplaceKeyFrame(const TimeStamp& _time_stamp, // + FrameBasePtr emplaceFrame(const TimeStamp& _time_stamp, // const Eigen::VectorXd& _frame_state); /** \brief Emplace frame, guess all values - * \param _frame_key_type Either KEY, AUXILIARY or NON_ESTIMATED + * \param _frame_key_type Either AUXILIARY or NON_ESTIMATED * \param _time_stamp Time stamp of the frame * * - The structure is taken from Problem @@ -302,11 +302,10 @@ class Problem : public std::enable_shared_from_this<Problem> * - Add it to Trajectory * - If it is key-frame, update state-block lists in Problem */ - FrameBasePtr emplaceKeyFrame(const TimeStamp& _time_stamp); + FrameBasePtr emplaceFrame(const TimeStamp& _time_stamp); // Frame getters FrameBasePtr getLastFrame( ) const; - FrameBasePtr getLastKeyOrAuxFrame( ) const; FrameBasePtr closestFrameToTimeStamp(const TimeStamp& _ts) const; /** \brief Give the permission to a processor to create a new key Frame @@ -325,22 +324,6 @@ class Problem : public std::enable_shared_from_this<Problem> ProcessorBasePtr _processor_ptr, // const double& _time_tolerance); - /** \brief Give the permission to a processor to create a new auxiliary Frame - * - * This should implement a black list of processors that have forbidden auxiliary frame creation. - * - This decision is made at problem level, not at processor configuration level. - * - Therefore, if you want to permanently configure a processor for not creating estimated frames, see Processor::voting_active_ and its accessors. - */ - bool permitAuxFrame(ProcessorBasePtr _processor_ptr) const; - - /** \brief New auxiliary frame callback - * - * New auxiliary frame callback: It should be called by any processor that creates a new auxiliary frame. It calls the auxiliaryFrameCallback of the processor motion. - */ - void auxFrameCallback(FrameBasePtr _frame_ptr, // - ProcessorBasePtr _processor_ptr, // - const double& _time_tolerance); - // State getters TimeStamp getTimeStamp ( ) const; VectorComposite getState ( const StateStructure& _structure = "" ) const; @@ -373,7 +356,6 @@ class Problem : public std::enable_shared_from_this<Problem> bool getCovarianceBlock(StateBlockPtr _state, Eigen::MatrixXd& _cov, const int _row_and_col = 0) const; bool getFrameCovariance(FrameBaseConstPtr _frame_ptr, Eigen::MatrixXd& _covariance) const; bool getLastFrameCovariance(Eigen::MatrixXd& _covariance) const; - bool getLastKeyOrAuxFrameCovariance(Eigen::MatrixXd& _covariance) const; bool getLandmarkCovariance(LandmarkBaseConstPtr _landmark_ptr, Eigen::MatrixXd& _covariance) const; diff --git a/include/core/processor/processor_base.h b/include/core/processor/processor_base.h index a7d3049a54aa576ccc2c0422f9e20e7744c08d27..c8945c8036ff54dc2e0fe2243b3ec0919c66eba4 100644 --- a/include/core/processor/processor_base.h +++ b/include/core/processor/processor_base.h @@ -227,7 +227,6 @@ struct ParamsProcessorBase : public ParamsBase { time_tolerance = _server.getParam<double>(prefix + _unique_name + "/time_tolerance"); voting_active = _server.getParam<bool>(prefix + _unique_name + "/keyframe_vote/voting_active"); - voting_aux_active = _server.getParam<bool>(prefix + _unique_name + "/keyframe_vote/voting_aux_active"); apply_loss_function = _server.getParam<bool>(prefix + _unique_name + "/apply_loss_function"); } @@ -239,13 +238,11 @@ struct ParamsProcessorBase : public ParamsBase */ double time_tolerance; bool voting_active; ///< Whether this processor is allowed to vote for a Key Frame or not - bool voting_aux_active; ///< Whether this processor is allowed to vote for an Auxiliary Frame or not bool apply_loss_function; ///< Whether this processor emplaces factors with loss function or not std::string print() const override { return "voting_active: " + std::to_string(voting_active) + "\n" - + "voting_aux_active: " + std::to_string(voting_aux_active) + "\n" + "time_tolerance: " + std::to_string(time_tolerance) + "\n" + "apply_loss_function: " + std::to_string(apply_loss_function) + "\n"; } @@ -337,19 +334,8 @@ class ProcessorBase : public NodeBase, public std::enable_shared_from_this<Proce */ virtual bool voteForKeyFrame() const = 0; - /** \brief Vote for Auxiliary Frame generation - * - * If a Auxiliary Frame criterion is validated, this function returns true, - * meaning that it wants to create a Auxiliary Frame at the \b last Capture. - * - * WARNING! This function only votes! It does not create Auxiliary Frames! - */ - virtual bool voteForAuxFrame() const {return false;}; - virtual bool permittedKeyFrame() final; - virtual bool permittedAuxFrame() final; - void setProblem(ProblemPtr) override; public: @@ -377,8 +363,6 @@ class ProcessorBase : public NodeBase, public std::enable_shared_from_this<Proce bool isVotingActive() const; - bool isVotingAuxActive() const; - void setVotingActive(bool _voting_active = true); int getDim() const; @@ -388,7 +372,6 @@ class ProcessorBase : public NodeBase, public std::enable_shared_from_this<Proce void link(SensorBasePtr); template<typename classType, typename... T> static std::shared_ptr<classType> emplace(SensorBasePtr _sen_ptr, T&&... all); - void setVotingAuxActive(bool _voting_active = true); virtual void printHeader(int depth, // bool constr_by, // @@ -439,21 +422,11 @@ inline bool ProcessorBase::isVotingActive() const return params_->voting_active; } -inline bool ProcessorBase::isVotingAuxActive() const -{ - return params_->voting_aux_active; -} - inline void ProcessorBase::setVotingActive(bool _voting_active) { params_->voting_active = _voting_active; } -inline void ProcessorBase::setVotingAuxActive(bool _voting_active) -{ - params_->voting_aux_active = _voting_active; -} - inline bool ProcessorBase::isMotion() const { // check if this inherits from IsMotion diff --git a/include/core/sensor/sensor_diff_drive.h b/include/core/sensor/sensor_diff_drive.h index cb08a2dd0ccb7967158aa2d9319d9b1fe210670b..212a955b19c1a76aecebaa90f7cc39be73f38a7a 100644 --- a/include/core/sensor/sensor_diff_drive.h +++ b/include/core/sensor/sensor_diff_drive.h @@ -37,7 +37,7 @@ struct ParamsSensorDiffDrive : public ParamsSensorBase prior_cov_diag = _server.getParam<Eigen::Vector3d>(prefix + _unique_name + "/prior_cov_diag"); ticks_cov_factor = _server.getParam<double>(prefix + _unique_name + "/ticks_cov_factor"); } - std::string print() const + std::string print() const override { return ParamsSensorBase::print() + "\n" + "radius_left: " + std::to_string(radius_left) + "\n" diff --git a/include/core/trajectory/trajectory_base.h b/include/core/trajectory/trajectory_base.h index cb89fa517f981153b84812b3382e852989d3f8a1..23939e2e81229de9bd4ab833ecf86ba2bddfb137 100644 --- a/include/core/trajectory/trajectory_base.h +++ b/include/core/trajectory/trajectory_base.h @@ -46,9 +46,6 @@ class TrajectoryRevIter : public std::map<TimeStamp, FrameBasePtr>::const_revers return std::map<TimeStamp, FrameBasePtr>::const_reverse_iterator::operator*().second; } }; -// typedef std::map<TimeStamp, FrameBasePtr> FrameMap; -// typedef std::map<TimeStamp, FrameBasePtr>::const_iterator TrajectoryIter; -// typedef std::map<TimeStamp, FrameBasePtr>::const_reverse_iterator TrajectoryRevIter; //class TrajectoryBase class TrajectoryBase : public NodeBase, public std::enable_shared_from_this<TrajectoryBase> @@ -104,14 +101,8 @@ class TrajectoryBase : public NodeBase, public std::enable_shared_from_this<Traj inline const FrameMap& TrajectoryBase::getFrameMap() const { return frame_map_; - // return frame_map_; } -// inline FrameBasePtr TrajectoryBase::getLastFrame() const -// { -// auto it = static_cast<TrajectoryRevIter>(frame_map_.rbegin()); -// return *it; -// } inline FrameBasePtr TrajectoryBase::getFirstFrame() const { auto it = static_cast<TrajectoryIter>(frame_map_.begin()); diff --git a/src/capture/capture_base.cpp b/src/capture/capture_base.cpp index d06149ba3f047bcca63f9e3d058e0220bbfb68bc..957ed68d0dff047513fb84d9d2f1781b7599b36c 100644 --- a/src/capture/capture_base.cpp +++ b/src/capture/capture_base.cpp @@ -152,14 +152,6 @@ bool CaptureBase::isConstrainedBy(const FactorBasePtr &_factor) const } -const StateStructure& CaptureBase::getStructure() const -{ - if (getSensor()) - return getSensor()->getStructure(); - else - return HasStateBlocks::getStructure(); -} - StateBlockPtr CaptureBase::getStateBlock(const char& _key) const { if (getSensor() and getSensor()->hasStateBlock(_key)) @@ -185,11 +177,9 @@ void CaptureBase::unfix() void CaptureBase::move(FrameBasePtr _frm_ptr) { - WOLF_WARN_COND(this->getFrame() == nullptr, "moving a capture not linked to any frame"); - WOLF_WARN_COND(_frm_ptr == nullptr, "moving a capture to a null FrameBasePtr"); + WOLF_WARN_COND(this->getFrame() == nullptr, "Moving Capture ", id(), " at ts=", getTimeStamp(), " not linked to any frame. Consider just linking it with link() instead of move()!"); - assert((this->getFrame() == nullptr || this->getFrame()->isKey()) && "Forbidden: moving a capture already linked to a KF"); - assert((_frm_ptr == nullptr || _frm_ptr->isKey()) && "Forbidden: moving a capture to a non-estimated frame"); + assert((this->getFrame() == nullptr || not this->getFrame()->getProblem()) && "Forbidden: trying to move a capture already linked to a KF!"); // Unlink if (this->getFrame()) @@ -227,7 +217,7 @@ void CaptureBase::setProblem(ProblemPtr _problem) if (_problem == nullptr || _problem == this->getProblem()) return; - assert(getFrame() and getFrame()->isKey()); + assert(getFrame() && "Cannot set problem: Capture has no Frame!"); NodeBase::setProblem(_problem); registerNewStateBlocks(_problem); @@ -244,6 +234,8 @@ 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(); + if(getSensor() != nullptr) { _stream << " -> Sen" << getSensor()->id(); @@ -268,7 +260,7 @@ void CaptureBase::printHeader(int _depth, bool _constr_by, bool _metric, bool _s { auto sb = getStateBlock(key); if (sb) - _stream << _tabs << key << "[" << (sb->isFixed() ? "Fix" : "Est") << "] = ( " << sb->getState().transpose() << " ) @ " << sb << std::endl; + _stream << " " + _tabs << key << "[" << (sb->isFixed() ? "Fix" : "Est") << "] = ( " << sb->getState().transpose() << " ) @ " << sb << std::endl; } } else if (_metric) @@ -405,7 +397,7 @@ CheckLog CaptureBase::localCheck(bool _verbose, CaptureBasePtr _cap_ptr, std::os match_any_prc_timetolerance = match_any_prc_timetolerance or (time_diff <= prc->getTimeTolerance()); } inconsistency_explanation << "Cap " << id() << " @ " << _cap_ptr - << " ts =" << getTimeStamp() << ((frame->isKey()) ? "KFrm" : "Frm") << frame->id() + << " ts =" << getTimeStamp() << "Frm" << frame->id() << " ts = " << frame->getTimeStamp() << " their time difference (" << time_diff << ") does not match any time tolerance of" << " any processor in sensor " << getSensor()->id() << "\n"; log.assertTrue((match_any_prc_timetolerance), inconsistency_explanation); diff --git a/src/ceres_wrapper/solver_ceres.cpp b/src/ceres_wrapper/solver_ceres.cpp index 7f33435f917a913eb4bf9cbf7b541634ac2a8e1c..67b009f243ace9d81664709c375a2008351cb73f 100644 --- a/src/ceres_wrapper/solver_ceres.cpp +++ b/src/ceres_wrapper/solver_ceres.cpp @@ -99,12 +99,11 @@ bool SolverCeres::computeCovariancesDerived(const CovarianceBlocksToBeComputed _ std::vector<StateBlockPtr> all_state_blocks, landmark_state_blocks; //frame state blocks for(auto fr_ptr : *wolf_problem_->getTrajectory()) - if (fr_ptr->isKey()) - for (const auto& key : fr_ptr->getStructure()) - { - const auto& sb = fr_ptr->getStateBlock(key); - all_state_blocks.push_back(sb); - } + for (const auto& key : fr_ptr->getStructure()) + { + const auto& sb = fr_ptr->getStateBlock(key); + all_state_blocks.push_back(sb); + } // landmark state blocks for(auto l_ptr : wolf_problem_->getMap()->getLandmarkList()) @@ -131,23 +130,22 @@ bool SolverCeres::computeCovariancesDerived(const CovarianceBlocksToBeComputed _ { // first create a vector containing all state blocks for(auto fr_ptr : *wolf_problem_->getTrajectory()) - if (fr_ptr->isKey()) - for (const auto& key1 : wolf_problem_->getFrameStructure()) + for (const auto& key1 : wolf_problem_->getFrameStructure()) + { + const auto& sb1 = fr_ptr->getStateBlock(key1); + assert(isStateBlockRegisteredDerived(sb1)); + + for (const auto& key2 : wolf_problem_->getFrameStructure()) { - const auto& sb1 = fr_ptr->getStateBlock(key1); - assert(isStateBlockRegisteredDerived(sb1)); - - for (const auto& key2 : wolf_problem_->getFrameStructure()) - { - const auto& sb2 = fr_ptr->getStateBlock(key2); - assert(isStateBlockRegisteredDerived(sb2)); - - state_block_pairs.emplace_back(sb1, sb2); - double_pairs.emplace_back(getAssociatedMemBlockPtr(sb1), getAssociatedMemBlockPtr(sb2)); - if (sb1 == sb2) - break; - } + const auto& sb2 = fr_ptr->getStateBlock(key2); + assert(isStateBlockRegisteredDerived(sb2)); + + state_block_pairs.emplace_back(sb1, sb2); + double_pairs.emplace_back(getAssociatedMemBlockPtr(sb1), getAssociatedMemBlockPtr(sb2)); + if (sb1 == sb2) + break; } + } // landmark state blocks for(auto l_ptr : wolf_problem_->getMap()->getLandmarkList()) diff --git a/src/factor/factor_base.cpp b/src/factor/factor_base.cpp index a0b4bc90005cb0ffa48c7ef21d87c758a7a52a36..c03fe00ad9b3a6018747b07572d0d6c1dbfd4a56 100644 --- a/src/factor/factor_base.cpp +++ b/src/factor/factor_base.cpp @@ -260,10 +260,6 @@ void FactorBase::link(FeatureBasePtr _ftr_ptr) _ftr_ptr->addFactor(shared_from_this()); this->setFeature(_ftr_ptr); - // if frame, should be key - if (getCapture() and getFrame()) - assert(getFrame()->isKey() && "Forbidden: linking a factor with a non-key frame."); - // set problem ( and register factor ) WOLF_WARN_COND(_ftr_ptr->getProblem() == nullptr, "ADDING FACTOR ", this->id(), " TO FEATURE ", _ftr_ptr->id(), " THAT IS NOT CONNECTED WITH PROBLEM."); this->setProblem(_ftr_ptr->getProblem()); @@ -274,7 +270,7 @@ void FactorBase::link(FeatureBasePtr _ftr_ptr) auto frame_other = frm_ow.lock(); if(frame_other != nullptr) { - assert(frame_other->isKey() && "Forbidden: linking a factor with a non-key frame_other."); + assert(frame_other->getProblem() && "Forbidden: linking a factor with a floating frame_other."); frame_other->addConstrainedBy(shared_from_this()); } } diff --git a/src/feature/feature_base.cpp b/src/feature/feature_base.cpp index b864e27c8172671572026ce4f83b4d279bb1b669..c2af9127c6a2e028d98f4f5413490117bfbd7825 100644 --- a/src/feature/feature_base.cpp +++ b/src/feature/feature_base.cpp @@ -194,7 +194,6 @@ void FeatureBase::printHeader(int _depth, bool _constr_by, bool _metric, bool _s void FeatureBase::print(int _depth, bool _constr_by, bool _metric, bool _state_blocks, std::ostream& _stream, std::string _tabs) const { - _stream << _tabs << "id: " << id() << std::endl; printHeader(_depth, _constr_by, _metric, _state_blocks, _stream, _tabs); if (_depth >= 4) for (auto c : getFactorList()) diff --git a/src/frame/frame_base.cpp b/src/frame/frame_base.cpp index 20ab9331867cd18963b5bc85b0f42fa1c01b4a2f..6207d6f1711d0431ebeb0039b4be462cece85371 100644 --- a/src/frame/frame_base.cpp +++ b/src/frame/frame_base.cpp @@ -12,15 +12,13 @@ namespace wolf { unsigned int FrameBase::frame_id_count_ = 0; -FrameBase::FrameBase(const FrameType & _tp, - const TimeStamp& _ts, +FrameBase::FrameBase(const TimeStamp& _ts, const std::string _frame_structure, const VectorComposite& _state) : NodeBase("FRAME", "FrameBase"), HasStateBlocks(_frame_structure), trajectory_ptr_(), frame_id_(++frame_id_count_), - type_(_tp), time_stamp_(_ts) { for (const auto& pair_key_vec : _state) @@ -35,15 +33,13 @@ FrameBase::FrameBase(const FrameType & _tp, } -FrameBase::FrameBase(const FrameType & _tp, - const TimeStamp& _ts, +FrameBase::FrameBase(const TimeStamp& _ts, const std::string _frame_structure, const std::list<VectorXd>& _vectors) : NodeBase("FRAME", "FrameBase"), HasStateBlocks(_frame_structure), trajectory_ptr_(), frame_id_(++frame_id_count_), - type_(_tp), time_stamp_(_ts) { assert(_frame_structure.size() == _vectors.size() && "Structure size does not match number of provided vectors!"); @@ -62,8 +58,7 @@ FrameBase::FrameBase(const FrameType & _tp, } -FrameBase::FrameBase(const FrameType & _tp, - const TimeStamp& _ts, +FrameBase::FrameBase(const TimeStamp& _ts, StateBlockPtr _p_ptr, StateBlockPtr _o_ptr, StateBlockPtr _v_ptr) : @@ -71,7 +66,6 @@ FrameBase::FrameBase(const FrameType & _tp, HasStateBlocks(""), trajectory_ptr_(), frame_id_(++frame_id_count_), - type_(_tp), time_stamp_(_ts) { if (_p_ptr) @@ -116,8 +110,7 @@ void FrameBase::remove(bool viral_remove_empty_parent) } // Remove Frame State Blocks - if ( isKey() ) - removeStateBlocks(getProblem()); + removeStateBlocks(getProblem()); // remove from upstream TrajectoryBasePtr T = trajectory_ptr_.lock(); @@ -133,20 +126,9 @@ void FrameBase::setTimeStamp(const TimeStamp& _ts) time_stamp_ = _ts; } -void FrameBase::setNonEstimated() +void FrameBase::link(ProblemPtr _prb) { - // unregister if previously estimated - if (isKey()) - for (const auto& sb : getStateBlockVec()) - getProblem()->notifyStateBlock(sb, REMOVE); - - type_ = NON_ESTIMATED; -} - -void FrameBase::setKey(ProblemPtr _prb) -{ - assert(_prb != nullptr && "setting Key fram with a null problem pointer"); - type_ = KEY; + assert(_prb != nullptr && "Trying to link Frame with a null problem pointer!"); this->link(_prb->getTrajectory()); } @@ -287,7 +269,6 @@ void FrameBase::link(TrajectoryBasePtr _trj_ptr) { assert(!is_removing_ && "linking a removed frame"); assert(this->getTrajectory() == nullptr && "linking an already linked frame"); - assert(isKey() && "Trying to link a non keyframe"); if(_trj_ptr) { @@ -303,8 +284,6 @@ void FrameBase::link(TrajectoryBasePtr _trj_ptr) void FrameBase::setProblem(ProblemPtr _problem) { - assert(isKey() && "Trying to setProblem to a non keyframe"); - if (_problem == nullptr || _problem == this->getProblem()) return; @@ -317,7 +296,7 @@ void FrameBase::setProblem(ProblemPtr _problem) void FrameBase::printHeader(int _depth, bool _constr_by, bool _metric, bool _state_blocks, std::ostream& _stream, std::string _tabs) const { - _stream << _tabs << (isKey() ? "KFrm" : "Frm") << id() + _stream << _tabs << "Frm" << id() << " " << getStructure() << " ts = " << std::setprecision(3) << getTimeStamp() << ((_depth < 2) ? " -- " + std::to_string(getCaptureList().size()) + "C " : ""); @@ -377,7 +356,7 @@ CheckLog FrameBase::localCheck(bool _verbose, FrameBasePtr _frm_ptr, std::ostrea std::stringstream inconsistency_explanation; if (_verbose) { - _stream << _tabs << (isKey() ? "KFrm" : "Frm") + _stream << _tabs << "Frm" << id() << " @ " << _frm_ptr.get() << std::endl; _stream << _tabs << " " << "-> Prb @ " << getProblem().get() << std::endl; _stream << _tabs << " " << "-> Trj @ " << getTrajectory().get() << std::endl; @@ -410,11 +389,6 @@ CheckLog FrameBase::localCheck(bool _verbose, FrameBasePtr _frm_ptr, std::ostrea << " different from Trajectory problem pointer " << trajectory_problem_ptr.get() << "\n"; log.assertTrue((getProblem() == trajectory_problem_ptr), inconsistency_explanation); - // // check trajectory pointer - // inconsistency_explanation << "Frame trajectory pointer is " << getTrajectory() - // << " but trajectory pointer is" << trajectory_ptr << "\n"; - // log.assertTrue((getTrajectory() == T, inconsistency_explanation); - // check constrained_by for (auto cby : getConstrainedByList()) { diff --git a/src/problem/problem.cpp b/src/problem/problem.cpp index bfcb33fa67482f2907ce1cdc715e4dacc44d60ed..3dceffdd79180d3bb3bd9f5d4a27d33321ace5b7 100644 --- a/src/problem/problem.cpp +++ b/src/problem/problem.cpp @@ -325,7 +325,7 @@ SensorBasePtr Problem::getSensor(const std::string& _sensor_name) const return (*sen_it); } -FrameBasePtr Problem::emplaceKeyFrame(const TimeStamp& _time_stamp, // +FrameBasePtr Problem::emplaceFrame(const TimeStamp& _time_stamp, // const StateStructure& _frame_structure, // const SizeEigen _dim, // const Eigen::VectorXd& _frame_state) @@ -347,60 +347,73 @@ FrameBasePtr Problem::emplaceKeyFrame(const TimeStamp& _time_stamp, // state.emplace(key, _frame_state.segment(index, size)); + // append new key to frame structure + if (frame_structure_.find(key) == std::string::npos) // not found + frame_structure_ += std::string(1,key); + index += size; } assert (_frame_state.size() == index && "State vector incompatible with given structure and dimension! Vector too large."); - auto frm = FrameBase::emplaceKeyFrame<FrameBase>(trajectory_ptr_, - _time_stamp, - _frame_structure, - state); + auto frm = FrameBase::emplace<FrameBase>(trajectory_ptr_, + _time_stamp, + _frame_structure, + state); + return frm; } -FrameBasePtr Problem::emplaceKeyFrame(const TimeStamp& _time_stamp, // +FrameBasePtr Problem::emplaceFrame(const TimeStamp& _time_stamp, // const StateStructure& _frame_structure, // const SizeEigen _dim) { - return emplaceKeyFrame(_time_stamp, - _frame_structure, - getState(_time_stamp)); + return emplaceFrame(_time_stamp, + _frame_structure, + getState(_time_stamp)); } -FrameBasePtr Problem::emplaceKeyFrame (const TimeStamp& _time_stamp, // - const StateStructure& _frame_structure, // - const VectorComposite& _frame_state) +FrameBasePtr Problem::emplaceFrame (const TimeStamp& _time_stamp, // + const StateStructure& _frame_structure, // + const VectorComposite& _frame_state) { - return FrameBase::emplaceKeyFrame<FrameBase>(getTrajectory(), - _time_stamp, - _frame_structure, - _frame_state); + return FrameBase::emplace<FrameBase>(getTrajectory(), + _time_stamp, + _frame_structure, + _frame_state); } -FrameBasePtr Problem::emplaceKeyFrame (const TimeStamp& _time_stamp, // +FrameBasePtr Problem::emplaceFrame (const TimeStamp& _time_stamp, // const VectorComposite& _frame_state) { - return FrameBase::emplaceKeyFrame<FrameBase>(getTrajectory(), - _time_stamp, - getFrameStructure(), - _frame_state); + // append new keys to frame structure + for (const auto& pair_key_vec : _frame_state) + { + const auto& key = pair_key_vec.first; + if (frame_structure_.find(key) == std::string::npos) // not found + frame_structure_ += std::string(1,key); + } + + return FrameBase::emplace<FrameBase>(getTrajectory(), + _time_stamp, + getFrameStructure(), + _frame_state); } -FrameBasePtr Problem::emplaceKeyFrame(const TimeStamp& _time_stamp, // - const Eigen::VectorXd& _frame_state) +FrameBasePtr Problem::emplaceFrame(const TimeStamp& _time_stamp, // + const Eigen::VectorXd& _frame_state) { - return emplaceKeyFrame(_time_stamp, - this->getFrameStructure(), - this->getDim(), - _frame_state); + return emplaceFrame(_time_stamp, + this->getFrameStructure(), + this->getDim(), + _frame_state); } -FrameBasePtr Problem::emplaceKeyFrame(const TimeStamp& _time_stamp) +FrameBasePtr Problem::emplaceFrame(const TimeStamp& _time_stamp) { - return emplaceKeyFrame(_time_stamp, - this->getFrameStructure(), - this->getDim()); + return emplaceFrame(_time_stamp, + this->getFrameStructure(), + this->getDim()); } TimeStamp Problem::getTimeStamp ( ) const @@ -639,31 +652,6 @@ void Problem::keyFrameCallback(FrameBasePtr _keyframe_ptr, ProcessorBasePtr _pro _processor_ptr->startCaptureProfiling(); } -bool Problem::permitAuxFrame(ProcessorBasePtr _processor_ptr) const -{ - // This should implement a black list of processors that have forbidden auxiliary frame creation - // This decision is made at problem level, not at processor configuration level. - // If you want to configure a processor for not creating auxiliary frames, see Processor::voting_active_ and its accessors. - - // Currently allowing all processors to vote: - return true; -} - -void Problem::auxFrameCallback(FrameBasePtr _frame_ptr, ProcessorBasePtr _processor_ptr, const double& _time_tolerance) -{ - // TODO -// if (_processor_ptr) -// { -// WOLF_DEBUG((_processor_ptr->isMotion() ? "PM " : "PT "), _processor_ptr->getName(), ": AuxF", _frame_ptr->id(), " Callback emitted with ts = ", _frame_ptr->getTimeStamp()); -// } -// else -// { -// WOLF_DEBUG("External callback: AuxF", _frame_ptr->id(), " Callback emitted with ts = ", _frame_ptr->getTimeStamp()); -// } -// -// processor_motion_ptr_->keyFrameCallback(_frame_ptr, _time_tolerance); -} - StateBlockPtr Problem::notifyStateBlock(StateBlockPtr _state_ptr, Notification _noti) { std::lock_guard<std::mutex> lock(mut_notifications_); @@ -1011,7 +999,7 @@ FrameBasePtr Problem::applyPriorOptions(const TimeStamp& _ts) if (prior_options_->mode != "nothing" and prior_options_->mode != "") { - prior_keyframe = emplaceKeyFrame(_ts, + prior_keyframe = emplaceFrame(_ts, prior_options_->state); if (prior_options_->mode == "fix") @@ -1174,12 +1162,9 @@ void Problem::perturb(double amplitude) // Frames and Captures for (auto& F : *(getTrajectory())) { - if (F->isKey()) - { - F->perturb(amplitude); - for (auto& C : F->getCaptureList()) - C->perturb(amplitude); - } + F->perturb(amplitude); + for (auto& C : F->getCaptureList()) + C->perturb(amplitude); } // Landmarks diff --git a/src/processor/processor_base.cpp b/src/processor/processor_base.cpp index 258e7c3d857a95f376b903c04977493be1d50e0d..7e1015a4dc5a30bb8a1ba475015001770956a0ec 100644 --- a/src/processor/processor_base.cpp +++ b/src/processor/processor_base.cpp @@ -33,11 +33,6 @@ bool ProcessorBase::permittedKeyFrame() return isVotingActive() && getProblem()->permitKeyFrame(shared_from_this()); } -bool ProcessorBase::permittedAuxFrame() -{ - return isVotingAuxActive() && getProblem()->permitAuxFrame(shared_from_this()); -} - void ProcessorBase::keyFrameCallback(FrameBasePtr _keyframe_ptr, const double& _time_tol_other) { assert(_keyframe_ptr != nullptr && "keyFrameCallback with a nullptr frame"); diff --git a/src/processor/processor_motion.cpp b/src/processor/processor_motion.cpp index bf44bb4a94fcd0d498b7b64ac8e4ec32c84b3827..c6fda0b6468a76644dfdf165240fdfdcf07949ba 100644 --- a/src/processor/processor_motion.cpp +++ b/src/processor/processor_motion.cpp @@ -423,7 +423,7 @@ void ProcessorMotion::processCapture(CaptureBasePtr _incoming_ptr) // Set the frame of last_ptr as key auto key_frame = last_ptr_->getFrame(); - key_frame ->setKey(getProblem()); + key_frame ->link(getProblem()); // create motion feature and add it to the key_capture auto key_feature = emplaceFeature(last_ptr_); @@ -432,9 +432,9 @@ void ProcessorMotion::processCapture(CaptureBasePtr _incoming_ptr) auto factor = emplaceFactor(key_feature, origin_ptr_); // create a new frame - auto frame_new = FrameBase::createNonKeyFrame<FrameBase>(getTimeStamp(), - getStateStructure(), - getProblem()->getState()); + auto frame_new = std::make_shared<FrameBase>(getTimeStamp(), + getStateStructure(), + getProblem()->getState()); // create a new capture auto capture_new = emplaceCapture(frame_new, getSensor(), @@ -662,10 +662,10 @@ VectorComposite ProcessorMotion::getState(const TimeStamp& _ts, const StateStruc FrameBasePtr ProcessorMotion::setOrigin(const VectorComposite& _x_origin, const TimeStamp& _ts_origin) { - FrameBasePtr key_frame_ptr = FrameBase::emplaceKeyFrame<FrameBase>(getProblem()->getTrajectory(), - _ts_origin, - getStateStructure(), - _x_origin); + FrameBasePtr key_frame_ptr = FrameBase::emplace<FrameBase>(getProblem()->getTrajectory(), + _ts_origin, + getStateStructure(), + _x_origin); setOrigin(key_frame_ptr); return key_frame_ptr; @@ -676,7 +676,6 @@ void ProcessorMotion::setOrigin(FrameBasePtr _origin_frame) assert(_origin_frame && "ProcessorMotion::setOrigin: Provided frame pointer is nullptr."); assert(_origin_frame->getTrajectory() != nullptr && "ProcessorMotion::setOrigin: origin frame must be in the trajectory."); - assert(_origin_frame->isKey() && "ProcessorMotion::setOrigin: origin frame must be KEY FRAME."); TimeStamp origin_ts = _origin_frame->getTimeStamp(); @@ -693,9 +692,9 @@ void ProcessorMotion::setOrigin(FrameBasePtr _origin_frame) // ---------- LAST ---------- // Make non-key-frame for last Capture - last_frame_ptr_ = FrameBase::createNonKeyFrame<FrameBase>(origin_ts, - getStateStructure(), - _origin_frame->getState()); + last_frame_ptr_ = std::make_shared<FrameBase>(origin_ts, + getStateStructure(), + _origin_frame->getState()); // emplace (emtpy) last Capture last_ptr_ = emplaceCapture(last_frame_ptr_, @@ -973,10 +972,10 @@ void ProcessorMotion::printHeader(int _depth, bool _constr_by, bool _metric, boo { _stream << _tabs << "PrcM" << id() << " " << getType() << " \"" << getName() << "\"" << std::endl; if (getOrigin()) - _stream << _tabs << " " << "o: Cap" << getOrigin()->id() << " - " << (getOrigin()->getFrame()->isKey() ? " KFrm" : " Frm" ) + _stream << _tabs << " " << "o: Cap" << getOrigin()->id() << " - " << " Frm" << getOrigin()->getFrame()->id() << std::endl; if (getLast()) - _stream << _tabs << " " << "l: Cap" << getLast()->id() << " - " << (getLast()->getFrame()->isKey() ? " KFrm" : " Frm") + _stream << _tabs << " " << "l: Cap" << getLast()->id() << " - " << " Frm" << getLast()->getFrame()->id() << std::endl; if (getIncoming()) _stream << _tabs << " " << "i: Cap" << getIncoming()->id() << std::endl; diff --git a/src/processor/processor_tracker.cpp b/src/processor/processor_tracker.cpp index 2e03aaafb52183adfd1843da41e0ca4ed3b49b3e..52421e86398bc049321e8b3dc5f75dc56d2d3001 100644 --- a/src/processor/processor_tracker.cpp +++ b/src/processor/processor_tracker.cpp @@ -81,10 +81,10 @@ void ProcessorTracker::processCapture(CaptureBasePtr _incoming_ptr) { WOLF_DEBUG( "PT ", getName(), " FIRST_TIME_WITHOUT_PACK" ); - FrameBasePtr kfrm = FrameBase::emplaceKeyFrame<FrameBase>(getProblem()->getTrajectory(), - incoming_ptr_->getTimeStamp(), - getProblem()->getFrameStructure(), - getProblem()->getState()); + FrameBasePtr kfrm = FrameBase::emplace<FrameBase>(getProblem()->getTrajectory(), + incoming_ptr_->getTimeStamp(), + getProblem()->getFrameStructure(), + getProblem()->getState()); incoming_ptr_->link(kfrm); // Process info @@ -114,9 +114,9 @@ void ProcessorTracker::processCapture(CaptureBasePtr _incoming_ptr) { WOLF_DEBUG( "PT ", getName(), " SECOND_TIME_WITHOUT_PACK" ); - FrameBasePtr frm = FrameBase::createNonKeyFrame<FrameBase>(incoming_ptr_->getTimeStamp(), - getProblem()->getFrameStructure(), - getProblem()->getState()); + FrameBasePtr frm = std::make_shared<FrameBase>(incoming_ptr_->getTimeStamp(), + getProblem()->getFrameStructure(), + getProblem()->getState()); incoming_ptr_->link(frm); // We have a last_ Capture with no features, so we do not process known features, and we do not vote for KF. @@ -151,9 +151,9 @@ void ProcessorTracker::processCapture(CaptureBasePtr _incoming_ptr) last_old_frame->remove(); // Create new frame - FrameBasePtr frm = FrameBase::createNonKeyFrame<FrameBase>(incoming_ptr_->getTimeStamp(), - getProblem()->getFrameStructure(), - getProblem()->getState()); + FrameBasePtr frm = std::make_shared<FrameBase>(incoming_ptr_->getTimeStamp(), + getProblem()->getFrameStructure(), + getProblem()->getState()); incoming_ptr_->link(frm); // Detect new Features, initialize Landmarks, create Factors, ... @@ -187,7 +187,7 @@ void ProcessorTracker::processCapture(CaptureBasePtr _incoming_ptr) // We create a KF // set KF on last last_ptr_->getFrame()->setState(getProblem()->getState(last_ptr_->getTimeStamp())); - last_ptr_->getFrame()->setKey(getProblem()); + last_ptr_->getFrame()->link(getProblem()); // // make F; append incoming to new F // FrameBasePtr frm = FrameBase::createNonKeyFrame<FrameBase>(incoming_ptr_->getTimeStamp()); @@ -203,9 +203,9 @@ void ProcessorTracker::processCapture(CaptureBasePtr _incoming_ptr) resetDerived(); // make F; append incoming to new F - FrameBasePtr frm = FrameBase::createNonKeyFrame<FrameBase>(incoming_ptr_->getTimeStamp(), - getProblem()->getFrameStructure(), - last_ptr_->getFrame()->getState()); + FrameBasePtr frm = std::make_shared<FrameBase>(incoming_ptr_->getTimeStamp(), + getProblem()->getFrameStructure(), + last_ptr_->getFrame()->getState()); incoming_ptr_->link(frm); origin_ptr_ = last_ptr_; last_ptr_ = incoming_ptr_; @@ -213,37 +213,6 @@ void ProcessorTracker::processCapture(CaptureBasePtr _incoming_ptr) incoming_ptr_ = nullptr; } - /* TODO: create an auxiliary frame - else if (voteForAuxFrame() && permittedAuxFrame()) - { - // We create an Auxiliary Frame - - // set AuxF on last - last_ptr_->getFrame()->setState(getProblem()->getState(last_ptr_->getTimeStamp())); - last_ptr_->getFrame()->setAuxiliary(); - - // make F; append incoming to new F - FrameBasePtr frm = FrameBase::createNonKeyFrame<FrameBase>(incoming_ptr_->getTimeStamp()); - incoming_ptr_->link(frm); - - // Establish factors - establishFactors(); - - // Call the new auxframe callback in order to let the ProcessorMotion to establish their factors - getProblem()->auxFrameCallback(last_ptr_->getFrame(), std::static_pointer_cast<ProcessorBase>(shared_from_this()), params_tracker_->time_tolerance); - - // Advance this - advanceDerived(); - - // Replace last frame for a new one in incoming - last_ptr_->getFrame()->addCapture(incoming_ptr_); // Add incoming Capture to the tracker's last Frame - // do not remove! last_ptr_->remove(); - incoming_ptr_->getFrame()->setTimeStamp(incoming_ptr_->getTimeStamp()); - - // Update pointers - last_ptr_ = incoming_ptr_; - incoming_ptr_ = nullptr; - }*/ else { // We do not create a KF @@ -252,9 +221,9 @@ void ProcessorTracker::processCapture(CaptureBasePtr _incoming_ptr) advanceDerived(); // Replace last frame for a new one in incoming - FrameBasePtr frm = FrameBase::createNonKeyFrame<FrameBase>(incoming_ptr_->getTimeStamp(), - getProblem()->getFrameStructure(), - last_ptr_->getFrame()->getState()); + FrameBasePtr frm = std::make_shared<FrameBase>(incoming_ptr_->getTimeStamp(), + getProblem()->getFrameStructure(), + last_ptr_->getFrame()->getState()); incoming_ptr_->link(frm); last_ptr_->getFrame()->remove(); // implicitly calling last_ptr_->remove(); @@ -307,11 +276,11 @@ void ProcessorTracker::computeProcessingStep() if (buffer_pack_kf_.selectPack(last_ptr_, params_tracker_->time_tolerance)) { - if (last_ptr_->getFrame()->isKey()) + if (last_ptr_->getFrame()->getProblem()) { WOLF_WARN("||*||"); WOLF_INFO(" ... It seems you missed something!"); - WOLF_INFO("Pack's KF and last's KF have matching time stamps (i.e. below time tolerances)"); + WOLF_INFO("Pack's KF and last's Frame have matching time stamps (i.e. below time tolerances)"); WOLF_INFO("Check the following for correctness:"); WOLF_INFO(" - You have all processors installed before starting receiving any data"); WOLF_INFO(" - You have configured all your processors with compatible time tolerances"); @@ -342,10 +311,10 @@ void ProcessorTracker::printHeader(int _depth, bool _constr_by, bool _metric, bo { _stream << _tabs << "PrcT" << id() << " " << getType() << " \"" << getName() << "\"" << std::endl; if (getOrigin()) - _stream << _tabs << " " << "o: Cap" << getOrigin()->id() << " - " << (getOrigin()->getFrame()->isKey() ? " KFrm" : " Frm") + _stream << _tabs << " " << "o: Cap" << getOrigin()->id() << " - " << " Frm" << getOrigin()->getFrame()->id() << std::endl; if (getLast()) - _stream << _tabs << " " << "l: Cap" << getLast()->id() << " - " << (getLast()->getFrame()->isKey() ? " KFrm" : " Frm") + _stream << _tabs << " " << "l: Cap" << getLast()->id() << " - " << " Frm" << getLast()->getFrame()->id() << std::endl; if (getIncoming()) _stream << _tabs << " " << "i: Cap" << getIncoming()->id() << std::endl; diff --git a/src/processor/track_matrix.cpp b/src/processor/track_matrix.cpp index 6d7dd0f50da30dc79e3c5c9cca980bc3364a0349..da6a88b75e98e0ada648f76155f5d12501c21c4d 100644 --- a/src/processor/track_matrix.cpp +++ b/src/processor/track_matrix.cpp @@ -214,7 +214,7 @@ Track TrackMatrix::trackAtKeyframes(size_t _track_id) const { auto& ts = pair_ts_ftr.first; auto& ftr = pair_ts_ftr.second; - if (ftr && ftr->getCapture() && ftr->getCapture()->getFrame() && ftr->getCapture()->getFrame()->isKey()) + if (ftr && ftr->getCapture() && ftr->getCapture()->getFrame() && ftr->getCapture()->getFrame()->getProblem()) track_kf[ts] = ftr; } return track_kf; diff --git a/src/trajectory/trajectory_base.cpp b/src/trajectory/trajectory_base.cpp index 23f967716a28e65d9aa09a01b1cb60a345f220e5..4a64613a3445bfead7565f38ae5527f01f2fde5c 100644 --- a/src/trajectory/trajectory_base.cpp +++ b/src/trajectory/trajectory_base.cpp @@ -6,7 +6,6 @@ namespace wolf { TrajectoryBase::TrajectoryBase() : NodeBase("TRAJECTORY", "TrajectoryBase") { -// WOLF_DEBUG("constructed T"); frame_map_ = FrameMap(); } diff --git a/src/yaml/processor_odom_3d_yaml.cpp b/src/yaml/processor_odom_3d_yaml.cpp index 9c21e3842304e475146194bc04da7be9f73de396..bd168ee20b162426a85d7b1b78e508f2c00a8fe1 100644 --- a/src/yaml/processor_odom_3d_yaml.cpp +++ b/src/yaml/processor_odom_3d_yaml.cpp @@ -34,7 +34,6 @@ static ParamsProcessorBasePtr createProcessorOdom3dParams(const std::string & _f YAML::Node keyframe_vote = config["keyframe_vote"]; params->voting_active = keyframe_vote["voting_active"] .as<bool>(); - params->voting_aux_active = keyframe_vote["voting_aux_active"].as<bool>(); params->max_time_span = keyframe_vote["max_time_span"] .as<double>(); params->max_buff_length = keyframe_vote["max_buff_length"] .as<SizeEigen>(); params->dist_traveled = keyframe_vote["dist_traveled"] .as<double>(); diff --git a/test/gtest_capture_base.cpp b/test/gtest_capture_base.cpp index 4c004cd72e14e9e69bb343e288ab86e3a5b9354e..3a0cbc4555c88bd40f0a656e2a73ff2a619654b6 100644 --- a/test/gtest_capture_base.cpp +++ b/test/gtest_capture_base.cpp @@ -100,6 +100,93 @@ TEST(CaptureBase, process) ASSERT_TRUE(C->process()); // This should not fail (although it does nothing) } +TEST(CaptureBase, move_from_F_to_KF) +{ + ProblemPtr problem = Problem::create("PO", 2); + + auto KF = problem->emplaceFrame(0.0); // dummy F object + + auto KC = CaptureBase::emplace<CaptureBase>(KF, "Dummy", 0.0); + + auto F = std::make_shared<FrameBase>(0.0, nullptr); // dummy F object + + auto C = CaptureBase::emplace<CaptureBase>(F, "Dummy", 0.0); + + ASSERT_EQ(KF->getCaptureList().size(), 1); + ASSERT_EQ(F->getCaptureList().size(), 1); + + C->move(KF); + + ASSERT_EQ(KF->getCaptureList().size(), 2); + ASSERT_EQ(F->getCaptureList().size(), 0); + ASSERT_TRUE(C->getProblem()); +} + +TEST(CaptureBase, move_from_F_to_null) +{ + ProblemPtr problem = Problem::create("PO", 2); + + FrameBasePtr F0 = nullptr; + + auto F = std::make_shared<FrameBase>(0.0, nullptr); // dummy F object + + auto C = CaptureBase::emplace<CaptureBase>(F, "Dummy", 0.0); + + ASSERT_EQ(F->getCaptureList().size(), 1); + + C->move(F0); + + ASSERT_EQ(F->getCaptureList().size(), 0); + ASSERT_FALSE(C->getProblem()); +} + +TEST(CaptureBase, move_from_null_to_KF) +{ + ProblemPtr problem = Problem::create("PO", 2); + + auto KF = problem->emplaceFrame(0.0); // dummy F object + + auto KC = CaptureBase::emplace<CaptureBase>(KF, "Dummy", 0.0); + + auto C = std::make_shared<CaptureBase>("Dummy", 0.0); + + ASSERT_EQ(KF->getCaptureList().size(), 1); + + C->move(KF); + + ASSERT_EQ(KF->getCaptureList().size(), 2); + ASSERT_TRUE(C->getProblem()); +} + +TEST(CaptureBase, move_from_null_to_F) +{ + ProblemPtr problem = Problem::create("PO", 2); + + auto F = std::make_shared<FrameBase>(0.0, nullptr); // dummy F object + + auto C = std::make_shared<CaptureBase>("Dummy", 0.0); + + C->move(F); + + ASSERT_EQ(F->getCaptureList().size(), 1); + + ASSERT_FALSE(C->getProblem()); +} + +TEST(CaptureBase, move_from_KF_to_F) +{ + ProblemPtr problem = Problem::create("PO", 2); + + auto KF = problem->emplaceFrame(0.0); // dummy F object + + auto F = std::make_shared<FrameBase>(0.0, nullptr); // dummy F object + + auto C = CaptureBase::emplace<CaptureBase>(KF, "Dummy", 0.0); + + ASSERT_DEATH(C->move(F), ""); +} + + int main(int argc, char **argv) { testing::InitGoogleTest(&argc, argv); diff --git a/test/gtest_emplace.cpp b/test/gtest_emplace.cpp index ebca6bb09bf463ed022aa81a1629e0accc877ff8..21ed3167006049866bcbc481ec5bfa81c760a23c 100644 --- a/test/gtest_emplace.cpp +++ b/test/gtest_emplace.cpp @@ -42,7 +42,7 @@ TEST(Emplace, Frame) ProblemPtr P = Problem::create("POV", 3); ASSERT_NE(P->getTrajectory(), nullptr); - FrameBase::emplaceKeyFrame<FrameBase>(P->getTrajectory(), TimeStamp(0), std::make_shared<StateBlock>(2,true), std::make_shared<StateBlock>(2,true)); + FrameBase::emplace<FrameBase>(P->getTrajectory(), TimeStamp(0), std::make_shared<StateBlock>(2,true), std::make_shared<StateBlock>(2,true)); ASSERT_EQ(P, P->getTrajectory()->getFirstFrame()->getTrajectory()->getProblem()); } @@ -67,7 +67,7 @@ TEST(Emplace, Capture) ProblemPtr P = Problem::create("POV", 3); ASSERT_NE(P->getTrajectory(), nullptr); - auto frm = FrameBase::emplaceKeyFrame<FrameBase>(P->getTrajectory(), TimeStamp(0), std::make_shared<StateBlock>(2,true), std::make_shared<StateBlock>(2,true)); + auto frm = FrameBase::emplace<FrameBase>(P->getTrajectory(), TimeStamp(0), std::make_shared<StateBlock>(2,true), std::make_shared<StateBlock>(2,true)); ASSERT_EQ(P, P->getTrajectory()->getFirstFrame()->getTrajectory()->getProblem()); auto cpt = CaptureBase::emplace<CaptureBase>(frm, "Dummy", TimeStamp(0), nullptr, nullptr, nullptr, nullptr); @@ -81,7 +81,7 @@ TEST(Emplace, Feature) ProblemPtr P = Problem::create("POV", 3); ASSERT_NE(P->getTrajectory(), nullptr); - auto frm = FrameBase::emplaceKeyFrame<FrameBase>(P->getTrajectory(), TimeStamp(0), std::make_shared<StateBlock>(2,true), std::make_shared<StateBlock>(2,true)); + auto frm = FrameBase::emplace<FrameBase>(P->getTrajectory(), TimeStamp(0), std::make_shared<StateBlock>(2,true), std::make_shared<StateBlock>(2,true)); ASSERT_EQ(P, P->getTrajectory()->getFirstFrame()->getTrajectory()->getProblem()); auto cpt = CaptureBase::emplace<CaptureBase>(frm, "Dummy", TimeStamp(0), nullptr, nullptr, nullptr, nullptr); @@ -99,7 +99,7 @@ TEST(Emplace, Factor) ProblemPtr P = Problem::create("POV", 3); ASSERT_NE(P->getTrajectory(), nullptr); - auto frm = FrameBase::emplaceKeyFrame<FrameBase>(P->getTrajectory(), TimeStamp(0), std::make_shared<StateBlock>(2,true), std::make_shared<StateBlock>(2,true)); + auto frm = FrameBase::emplace<FrameBase>(P->getTrajectory(), TimeStamp(0), std::make_shared<StateBlock>(2,true), std::make_shared<StateBlock>(2,true)); ASSERT_EQ(P, P->getTrajectory()->getFirstFrame()->getTrajectory()->getProblem()); auto cpt = CaptureBase::emplace<CaptureBase>(frm, "Dummy", TimeStamp(0), nullptr, nullptr, nullptr, nullptr); @@ -119,7 +119,7 @@ TEST(Emplace, EmplaceDerived) { ProblemPtr P = Problem::create("POV", 3); - auto frm = FrameBase::emplaceKeyFrame<FrameBase>(P->getTrajectory(), TimeStamp(0), std::make_shared<StateBlock>(2,true), std::make_shared<StateBlock>(2,true)); + auto frm = FrameBase::emplace<FrameBase>(P->getTrajectory(), TimeStamp(0), std::make_shared<StateBlock>(2,true), std::make_shared<StateBlock>(2,true)); auto sen = SensorBase::emplace<SensorOdom2d>(P->getHardware(), Eigen::VectorXd(3), ParamsSensorOdom2d()); auto cov = Eigen::MatrixXd::Identity(2,2); auto cpt = CaptureBase::emplace<CaptureOdom2d>(frm, TimeStamp(0), sen, Eigen::VectorXd(2), cov, nullptr); @@ -141,7 +141,7 @@ TEST(Emplace, ReturnDerived) ProblemPtr P = Problem::create("POV", 3); ASSERT_NE(P->getTrajectory(), nullptr); - auto frm = FrameBase::emplaceKeyFrame<FrameBase>(P->getTrajectory(), TimeStamp(0), std::make_shared<StateBlock>(2,true), std::make_shared<StateBlock>(2,true)); + auto frm = FrameBase::emplace<FrameBase>(P->getTrajectory(), TimeStamp(0), std::make_shared<StateBlock>(2,true), std::make_shared<StateBlock>(2,true)); auto cpt = CaptureBase::emplace<CaptureBase>(frm, "Dummy", TimeStamp(0), nullptr, nullptr, nullptr, nullptr); auto cov = Eigen::MatrixXd::Identity(2,2); auto ftr = FeatureBase::emplace<FeatureOdom2d>(cpt, Eigen::VectorXd(2), cov); diff --git a/test/gtest_factor_absolute.cpp b/test/gtest_factor_absolute.cpp index 8c3b353ccb9493be57f2d38a6ffe257a6375f3b8..dc3551d2c79d47973e4dca81d4046fa1f669661d 100644 --- a/test/gtest_factor_absolute.cpp +++ b/test/gtest_factor_absolute.cpp @@ -35,7 +35,7 @@ ProblemPtr problem_ptr = Problem::create("POV", 3); SolverCeres solver(problem_ptr); // Two frames -FrameBasePtr frm0 = problem_ptr->emplaceKeyFrame(0, problem_ptr->stateZero() ); +FrameBasePtr frm0 = problem_ptr->emplaceFrame(0, problem_ptr->stateZero() ); // Capture // auto cap0 = CaptureBase::emplace<CaptureMotion>(frm0, "IMU ABS", 0, nullptr, pose10, 10, 9, nullptr); diff --git a/test/gtest_factor_autodiff.cpp b/test/gtest_factor_autodiff.cpp index 0acd77891bf1bae60fe41575edec629e9864999b..f4e3108d6bdf2e129358b851e82772dc5cffae3a 100644 --- a/test/gtest_factor_autodiff.cpp +++ b/test/gtest_factor_autodiff.cpp @@ -350,8 +350,11 @@ TEST(FactorAutodiff, AutodiffDummy12) TEST(FactorAutodiff, EmplaceOdom2d) { - FrameBasePtr fr1_ptr(std::make_shared<FrameBase>(KEY, TimeStamp(0), std::make_shared<StateBlock>(2), std::make_shared<StateBlock>(1))); - FrameBasePtr fr2_ptr(std::make_shared<FrameBase>(KEY, TimeStamp(0), std::make_shared<StateBlock>(2), std::make_shared<StateBlock>(1))); + + ProblemPtr problem = Problem::create("PO", 2); + + FrameBasePtr fr1_ptr = problem->emplaceFrame(TimeStamp(1)); + FrameBasePtr fr2_ptr = problem->emplaceFrame(TimeStamp(2)); // SENSOR ParamsSensorOdom2d intrinsics_odo; @@ -377,12 +380,14 @@ TEST(FactorAutodiff, EmplaceOdom2d) TEST(FactorAutodiff, ResidualOdom2d) { + ProblemPtr problem = Problem::create("PO", 2); + Eigen::Vector3d f1_pose, f2_pose; f1_pose << 2,1,M_PI; f2_pose << 3,5,3*M_PI/2; - FrameBasePtr fr1_ptr(std::make_shared<FrameBase>(KEY, TimeStamp(0), std::make_shared<StateBlock>(f1_pose.head<2>()), std::make_shared<StateBlock>(f1_pose.tail<1>()))); - FrameBasePtr fr2_ptr(std::make_shared<FrameBase>(KEY, TimeStamp(0), std::make_shared<StateBlock>(f2_pose.head<2>()), std::make_shared<StateBlock>(f2_pose.tail<1>()))); + FrameBasePtr fr1_ptr = problem->emplaceFrame(TimeStamp(1), f1_pose); + FrameBasePtr fr2_ptr = problem->emplaceFrame(TimeStamp(2), f2_pose); // SENSOR ParamsSensorOdom2d intrinsics_odo; @@ -421,12 +426,14 @@ TEST(FactorAutodiff, ResidualOdom2d) TEST(FactorAutodiff, JacobianOdom2d) { + ProblemPtr problem = Problem::create("PO", 2); + Eigen::Vector3d f1_pose, f2_pose; f1_pose << 2,1,M_PI; f2_pose << 3,5,3*M_PI/2; - FrameBasePtr fr1_ptr(std::make_shared<FrameBase>(KEY, TimeStamp(0), std::make_shared<StateBlock>(f1_pose.head<2>()), std::make_shared<StateBlock>(f1_pose.tail<1>()))); - FrameBasePtr fr2_ptr(std::make_shared<FrameBase>(KEY, TimeStamp(0), std::make_shared<StateBlock>(f2_pose.head<2>()), std::make_shared<StateBlock>(f2_pose.tail<1>()))); + FrameBasePtr fr1_ptr = problem->emplaceFrame(TimeStamp(1), f1_pose); + FrameBasePtr fr2_ptr = problem->emplaceFrame(TimeStamp(2), f2_pose); // SENSOR ParamsSensorOdom2d intrinsics_odo; @@ -499,12 +506,14 @@ TEST(FactorAutodiff, JacobianOdom2d) TEST(FactorAutodiff, AutodiffVsAnalytic) { + ProblemPtr problem = Problem::create("PO", 2); + Eigen::Vector3d f1_pose, f2_pose; f1_pose << 2,1,M_PI; f2_pose << 3,5,3*M_PI/2; - FrameBasePtr fr1_ptr(std::make_shared<FrameBase>(KEY, TimeStamp(0), std::make_shared<StateBlock>(f1_pose.head<2>()), std::make_shared<StateBlock>(f1_pose.tail<1>()))); - FrameBasePtr fr2_ptr(std::make_shared<FrameBase>(KEY, TimeStamp(0), std::make_shared<StateBlock>(f2_pose.head<2>()), std::make_shared<StateBlock>(f2_pose.tail<1>()))); + FrameBasePtr fr1_ptr = problem->emplaceFrame(TimeStamp(1), f1_pose); + FrameBasePtr fr2_ptr = problem->emplaceFrame(TimeStamp(2), f2_pose); // SENSOR ParamsSensorOdom2d intrinsics_odo; diff --git a/test/gtest_factor_autodiff_distance_3d.cpp b/test/gtest_factor_autodiff_distance_3d.cpp index 3e6974cb91303c8f864db2816d801207eba309ad..fa3d365424b3d62aa56eb6e6d186163251a594ad 100644 --- a/test/gtest_factor_autodiff_distance_3d.cpp +++ b/test/gtest_factor_autodiff_distance_3d.cpp @@ -55,9 +55,9 @@ class FactorAutodiffDistance3d_Test : public testing::Test problem = Problem::create("PO", 3); solver = std::make_shared<SolverCeres>(problem); - F1 = problem->emplaceKeyFrame (1.0, pose1); + F1 = problem->emplaceFrame (1.0, pose1); - F2 = problem->emplaceKeyFrame (2.0, pose2); + F2 = problem->emplaceFrame (2.0, pose2); C2 = CaptureBase::emplace<CaptureBase>(F2, "Base", 1.0); } diff --git a/test/gtest_factor_base.cpp b/test/gtest_factor_base.cpp index e1e035bf0ae084d309b51db84b4c49ac62440924..79663676a51ea74c3ea2fc23f5c32c5e18e1cf30 100644 --- a/test/gtest_factor_base.cpp +++ b/test/gtest_factor_base.cpp @@ -24,8 +24,8 @@ class FactorBaseTest : public testing::Test void SetUp() override { - F0 = std::make_shared<FrameBase>(KEY, 0.0, nullptr); - F1 = std::make_shared<FrameBase>(KEY, 1.0, nullptr); + F0 = std::make_shared<FrameBase>(0.0, nullptr); + F1 = std::make_shared<FrameBase>(1.0, nullptr); C0 = std::make_shared<CaptureBase>("Capture", 0.0, nullptr); C1 = std::make_shared<CaptureBase>("Capture", 1.0, nullptr); f0 = std::make_shared<FeatureBase>("Feature", Vector2d(1,2), Matrix2d::Identity(), FeatureBase::UncertaintyType::UNCERTAINTY_IS_COVARIANCE); diff --git a/test/gtest_factor_block_difference.cpp b/test/gtest_factor_block_difference.cpp index 9b572504fa686bd555ba3b5ec25f39d1a4fb7afd..1dbf21b97b609ae212b1e88cf16ef993c2e742dc 100644 --- a/test/gtest_factor_block_difference.cpp +++ b/test/gtest_factor_block_difference.cpp @@ -58,7 +58,7 @@ class FixtureFactorBlockDifference : public testing::Test //FeatureBasePtr featV0 = FeatureBase::emplace<FeatureBase>(capV0, "Vel0", x_origin.tail(3), cov_prior.bottomRightCorner<3,3>()); //FactorBasePtr facV0 = FactorBase::emplace<FactorBlockAbsolute>(featV0, KF0_->getV(), nullptr, false); - KF1_ = problem_->emplaceKeyFrame(t1, problem_->stateZero()); + KF1_ = problem_->emplaceFrame(t1, problem_->stateZero()); Cap_ = CaptureBase::emplace<CaptureBase>(KF1_, "BlockDifference", t1); } diff --git a/test/gtest_factor_diff_drive.cpp b/test/gtest_factor_diff_drive.cpp index 51661f8ab26d1257f43dd4d4cbcc8dd5237b80d8..4f3ece70d92af1deeb923ce811d7a09dd96ba543 100644 --- a/test/gtest_factor_diff_drive.cpp +++ b/test/gtest_factor_diff_drive.cpp @@ -159,11 +159,11 @@ class FactorDiffDriveTest : public testing::Test processor = std::static_pointer_cast<ProcessorDiffDrivePublic>(prc); // frames - F0 = FrameBase::emplaceKeyFrame<FrameBase>(trajectory, + F0 = FrameBase::emplace<FrameBase>(trajectory, 0.0, "PO", std::list<VectorXd>{Vector2d(0,0), Vector1d(0)}); - F1 = FrameBase::emplaceKeyFrame<FrameBase>(trajectory, + F1 = FrameBase::emplace<FrameBase>(trajectory, 1.0, "PO", std::list<VectorXd>{Vector2d(1,0), Vector1d(0)}); diff --git a/test/gtest_factor_odom_2d.cpp b/test/gtest_factor_odom_2d.cpp index baee1dddcaf2c1fb998e3ae551f29a39a335fd5b..740933a67158634dfd7c6194c8b6a46bd926c063 100644 --- a/test/gtest_factor_odom_2d.cpp +++ b/test/gtest_factor_odom_2d.cpp @@ -19,8 +19,8 @@ ProblemPtr problem_ptr = Problem::create("PO", 2); SolverCeres solver(problem_ptr); // Two frames -FrameBasePtr frm0 = problem_ptr->emplaceKeyFrame(TimeStamp(0), Vector3d::Zero()); -FrameBasePtr frm1 = problem_ptr->emplaceKeyFrame(TimeStamp(1), Vector3d::Zero()); +FrameBasePtr frm0 = problem_ptr->emplaceFrame(TimeStamp(0), Vector3d::Zero()); +FrameBasePtr frm1 = problem_ptr->emplaceFrame(TimeStamp(1), Vector3d::Zero()); // Capture from frm1 to frm0 auto cap1 = CaptureBase::emplace<CaptureOdom2d>(frm1, 1, nullptr, Vector3d::Zero(), data_cov); diff --git a/test/gtest_factor_odom_3d.cpp b/test/gtest_factor_odom_3d.cpp index 24daac332094bb8e65964eb0acdd9346341eb3f9..7a57f0354a19c2a53e8ce6adac68f07713a93664 100644 --- a/test/gtest_factor_odom_3d.cpp +++ b/test/gtest_factor_odom_3d.cpp @@ -37,8 +37,8 @@ ProblemPtr problem_ptr = Problem::create("PO", 3); SolverCeres solver(problem_ptr); // Two frames -FrameBasePtr frm0 = problem_ptr->emplaceKeyFrame(TimeStamp(0), problem_ptr->stateZero()); -FrameBasePtr frm1 = problem_ptr->emplaceKeyFrame(TimeStamp(1), delta); +FrameBasePtr frm0 = problem_ptr->emplaceFrame(TimeStamp(0), problem_ptr->stateZero()); +FrameBasePtr frm1 = problem_ptr->emplaceFrame(TimeStamp(1), delta); // Capture, feature and factor from frm1 to frm0 auto cap1 = CaptureBase::emplace<CaptureMotion>(frm1, "CaptureOdom3d", 1, nullptr, delta, nullptr); diff --git a/test/gtest_factor_pose_2d.cpp b/test/gtest_factor_pose_2d.cpp index 749d514d8cc4c0479cfdf5092dca6e5face76ea8..7ecc6ab0848695e7922d9e9fb83f92a73a95e861 100644 --- a/test/gtest_factor_pose_2d.cpp +++ b/test/gtest_factor_pose_2d.cpp @@ -30,7 +30,7 @@ ProblemPtr problem = Problem::create("PO", 2); SolverCeres solver(problem); // Two frames -FrameBasePtr frm0 = problem->emplaceKeyFrame(TimeStamp(0), problem->stateZero()); +FrameBasePtr frm0 = problem->emplaceFrame(TimeStamp(0), problem->stateZero()); // Capture, feature and factor from frm1 to frm0 auto cap0 = CaptureBase::emplace<CaptureMotion>(frm0, "CaptureOdom2d", 0, nullptr, pose, nullptr); diff --git a/test/gtest_factor_pose_3d.cpp b/test/gtest_factor_pose_3d.cpp index 88433b4b4433ce7e5290c81b34766d13fb2f9831..c44374caa2a908080d36e5396a9e41db846b7fb7 100644 --- a/test/gtest_factor_pose_3d.cpp +++ b/test/gtest_factor_pose_3d.cpp @@ -36,7 +36,7 @@ ProblemPtr problem = Problem::create("PO", 3); SolverCeres solver(problem); // Two frames -FrameBasePtr frm0 = problem->emplaceKeyFrame(0, problem->stateZero() ); +FrameBasePtr frm0 = problem->emplaceFrame(0, problem->stateZero() ); // Capture, feature and factor auto cap0 = CaptureBase::emplace<CaptureMotion>(frm0, "CaptureOdom3d", 0, nullptr, pose7, nullptr); diff --git a/test/gtest_factor_relative_2d_analytic.cpp b/test/gtest_factor_relative_2d_analytic.cpp index 93581a6ac63b18da056f84ea5caed95ca009ebd4..70cbc464716d50d60bb8ad05cfdb1a4bd6f79d95 100644 --- a/test/gtest_factor_relative_2d_analytic.cpp +++ b/test/gtest_factor_relative_2d_analytic.cpp @@ -19,8 +19,8 @@ ProblemPtr problem_ptr = Problem::create("PO", 2); SolverCeres solver(problem_ptr); // Two frames -FrameBasePtr frm0 = problem_ptr->emplaceKeyFrame(0.0, Vector3d::Zero()); -FrameBasePtr frm1 = problem_ptr->emplaceKeyFrame(1.0, Vector3d::Zero()); +FrameBasePtr frm0 = problem_ptr->emplaceFrame(0.0, Vector3d::Zero()); +FrameBasePtr frm1 = problem_ptr->emplaceFrame(1.0, Vector3d::Zero()); // Capture from frm1 to frm0 auto cap1 = CaptureBase::emplace<CaptureOdom2d>(frm1, 1, nullptr, Vector3d::Zero(), data_cov); diff --git a/test/gtest_factor_relative_pose_2d_with_extrinsics.cpp b/test/gtest_factor_relative_pose_2d_with_extrinsics.cpp index 78321478cc5126e419ca4fc8fea53c5ed79caa71..f6e8e18f10247e1c819121bc9e4494dd26ac6efe 100644 --- a/test/gtest_factor_relative_pose_2d_with_extrinsics.cpp +++ b/test/gtest_factor_relative_pose_2d_with_extrinsics.cpp @@ -27,8 +27,8 @@ auto sensor_odom2d = problem_ptr->installSensor("SensorOdom2d", "odom", Vector3d auto processor_odom2d = problem_ptr->installProcessor("ProcessorOdom2d", "odom", sensor_odom2d, std::make_shared<ParamsProcessorOdom2d>()); // Two frames -FrameBasePtr frm0 = problem_ptr->emplaceKeyFrame(0, Vector3d::Zero() ); -FrameBasePtr frm1 = problem_ptr->emplaceKeyFrame(1, Vector3d::Zero() ); +FrameBasePtr frm0 = problem_ptr->emplaceFrame(0, Vector3d::Zero() ); +FrameBasePtr frm1 = problem_ptr->emplaceFrame(1, Vector3d::Zero() ); // Capture from frm1 to frm0 auto cap1 = CaptureBase::emplace<CaptureOdom2d>(frm1, 1, sensor_odom2d, Vector3d::Zero(), data_cov); @@ -40,7 +40,7 @@ TEST(FactorRelativePose2dWithExtrinsics, check_tree) TEST(FactorRelativePose2dWithExtrinsics, fix_0_solve) { - for (int i = 0; i < 1e3; i++) + for (int i = 0; i < 1e2; i++) { // Random delta Vector3d delta = Vector3d::Random() * 10; @@ -88,7 +88,7 @@ TEST(FactorRelativePose2dWithExtrinsics, fix_0_solve) TEST(FactorRelativePose2dWithExtrinsics, fix_1_solve) { - for (int i = 0; i < 1e3; i++) + for (int i = 0; i < 1e2; i++) { // Random delta Vector3d delta = Vector3d::Random() * 10; @@ -136,7 +136,7 @@ TEST(FactorRelativePose2dWithExtrinsics, fix_1_solve) TEST(FactorRelativePose2dWithExtrinsics, extrinsics_p_solve) { - for (int i = 0; i < 1e3; i++) + for (int i = 0; i < 1e2; i++) { // Random delta Vector3d delta = Vector3d::Random() * 10; @@ -184,7 +184,7 @@ TEST(FactorRelativePose2dWithExtrinsics, extrinsics_p_solve) TEST(FactorRelativePose2dWithExtrinsics, extrinsics_o_solve) { - for (int i = 0; i < 1e3; i++) + for (int i = 0; i < 1e2; i++) { // Random delta Vector3d delta = Vector3d::Random() * 10; diff --git a/test/gtest_frame_base.cpp b/test/gtest_frame_base.cpp index 7167566535827fa6281057903e6f11dafdf3810d..ac405e6fa1e9f4bcdc7976d8f0adc2014cb79c5f 100644 --- a/test/gtest_frame_base.cpp +++ b/test/gtest_frame_base.cpp @@ -22,7 +22,7 @@ using namespace wolf; TEST(FrameBase, GettersAndSetters) { - FrameBasePtr F = make_shared<FrameBase>(NON_ESTIMATED, 1, make_shared<StateBlock>(2), make_shared<StateBlock>(1)); + FrameBasePtr F = make_shared<FrameBase>(1, make_shared<StateBlock>(2), make_shared<StateBlock>(1)); // getters ASSERT_EQ(F->id(), (unsigned int) 1); @@ -31,13 +31,11 @@ TEST(FrameBase, GettersAndSetters) F->getTimeStamp(t); ASSERT_EQ(t, 1); ASSERT_FALSE(F->isFixed()); - ASSERT_EQ(F->isKey(), false); - ASSERT_EQ(F->isKey(), false); } TEST(FrameBase, StateBlocks) { - FrameBasePtr F = make_shared<FrameBase>(NON_ESTIMATED, 1, make_shared<StateBlock>(2), make_shared<StateBlock>(1)); + FrameBasePtr F = make_shared<FrameBase>(1, make_shared<StateBlock>(2), make_shared<StateBlock>(1)); ASSERT_EQ(F->getStateBlockMap().size(),(unsigned int) 2); ASSERT_EQ(F->getP()->getState().size(),(unsigned int) 2); @@ -47,12 +45,10 @@ TEST(FrameBase, StateBlocks) TEST(FrameBase, LinksBasic) { - FrameBasePtr F = make_shared<FrameBase>(NON_ESTIMATED, 1, make_shared<StateBlock>(2), make_shared<StateBlock>(1)); + FrameBasePtr F = make_shared<FrameBase>(1, make_shared<StateBlock>(2), make_shared<StateBlock>(1)); ASSERT_FALSE(F->getTrajectory()); ASSERT_FALSE(F->getProblem()); - // ASSERT_THROW(f->getPreviousFrame(), std::runtime_error); // protected by assert() - // ASSERT_EQ(f->getStatus(), ST_ESTIMATED); // protected SensorOdom2dPtr S = make_shared<SensorOdom2d>(Vector3d::Zero(), ParamsSensorOdom2d()); ASSERT_FALSE(F->getCaptureOf(S)); ASSERT_TRUE(F->getCaptureList().empty()); @@ -69,8 +65,8 @@ TEST(FrameBase, LinksToTree) intrinsics_odo.k_disp_to_disp = 1; intrinsics_odo.k_rot_to_rot = 1; auto S = SensorBase::emplace<SensorOdom2d>(P->getHardware(), Vector3d::Zero(), intrinsics_odo); - auto F1 = FrameBase::emplaceKeyFrame<FrameBase>(T, 1, make_shared<StateBlock>(2), make_shared<StateBlock>(1)); - auto F2 = FrameBase::emplaceKeyFrame<FrameBase>(T, 2, make_shared<StateBlock>(2), make_shared<StateBlock>(1)); + auto F1 = FrameBase::emplace<FrameBase>(T, 1, make_shared<StateBlock>(2), make_shared<StateBlock>(1)); + auto F2 = FrameBase::emplace<FrameBase>(T, 2, make_shared<StateBlock>(2), make_shared<StateBlock>(1)); auto C = CaptureBase::emplace<CaptureMotion>(F1, "CaptureMotion", 1, S, Vector3d::Zero(), nullptr); WOLF_INFO("F2->getCaptureList().size() ", F2->getCaptureList().size()); auto p = std::make_shared<ProcessorOdom2d>(std::make_shared<ParamsProcessorOdom2d>()); @@ -115,8 +111,6 @@ TEST(FrameBase, LinksToTree) ASSERT_FALSE(F1->isFixed()); F1->getO()->fix(); ASSERT_TRUE(F1->isFixed()); - - ASSERT_TRUE(F1->isKey()); } #include "core/state_block/state_quaternion.h" @@ -128,7 +122,7 @@ TEST(FrameBase, GetSetState) StateQuaternionPtr sbq = make_shared<StateQuaternion>(); // Create frame - FrameBase F(NON_ESTIMATED, 1, sbp, sbq, sbv); + FrameBase F(1, sbp, sbq, sbv); // Give values to vectors and vector blocks VectorXd x(10), x1(10), x2(10); @@ -152,12 +146,10 @@ TEST(FrameBase, GetSetState) TEST(FrameBase, Constructor_composite) { - FrameBase F = FrameBase(KEY, - 0.0, + FrameBase F = FrameBase(0.0, "POV", VectorComposite("POV", {Vector3d(1,2,3), Vector4d(1,2,3,4).normalized(), Vector3d(1,2,3)})); - ASSERT_TRUE (F.isKey()); ASSERT_MATRIX_APPROX(F.getP()->getState(), Vector3d(1,2,3), 1e-15); ASSERT_TRUE (F.getO()->hasLocalParametrization()); ASSERT_EQ (F.getStateBlock('V')->getSize(), 3); @@ -165,12 +157,10 @@ TEST(FrameBase, Constructor_composite) TEST(FrameBase, Constructor_vectors) { - FrameBase F = FrameBase(KEY, - 0.0, + FrameBase F = FrameBase(0.0, "POV", {Vector3d(1,2,3), Vector4d(1,2,3,4).normalized(), Vector3d(1,2,3)}); - ASSERT_TRUE (F.isKey()); ASSERT_MATRIX_APPROX(F.getP()->getState(), Vector3d(1,2,3), 1e-15); ASSERT_TRUE (F.getO()->hasLocalParametrization()); ASSERT_EQ (F.getStateBlock('V')->getSize(), 3); diff --git a/test/gtest_has_state_blocks.cpp b/test/gtest_has_state_blocks.cpp index 646dd602e619b0c2d2fadd70eb6c6f94e7f79a5f..0d42d813257b1b2b26aeefe3fb908a3b29b5b616 100644 --- a/test/gtest_has_state_blocks.cpp +++ b/test/gtest_has_state_blocks.cpp @@ -41,8 +41,8 @@ class HasStateBlocksTest : public testing::Test sbo1 = std::make_shared<StateQuaternion>(); sbv1 = std::make_shared<StateBlock>(3); // size 3 - F0 = std::make_shared<FrameBase>(NON_ESTIMATED, 0.0, sbp0, sbo0); // non KF - F1 = std::make_shared<FrameBase>(NON_ESTIMATED, 1.0, nullptr); // non KF + F0 = std::make_shared<FrameBase>(0.0, sbp0, sbo0); // non KF + F1 = std::make_shared<FrameBase>(1.0, nullptr); // non KF } void TearDown() override{} @@ -50,21 +50,6 @@ class HasStateBlocksTest : public testing::Test }; -TEST_F(HasStateBlocksTest, Notifications_setKey_add) -{ - Notification n; - ASSERT_FALSE(problem->getStateBlockNotification(sbp0, n)); - - ASSERT_DEATH(F0->link(problem->getTrajectory()), ""); - - // ASSERT_FALSE(problem->getStateBlockNotification(sbp0, n)); - - F0->setKey(problem); - - ASSERT_TRUE(problem->getStateBlockNotification(sbp0, n)); - ASSERT_EQ(n, ADD); -} - TEST_F(HasStateBlocksTest, Notifications_add_makeKF) { Notification n; @@ -83,7 +68,7 @@ TEST_F(HasStateBlocksTest, Notifications_add_makeKF) ASSERT_FALSE(problem->getStateBlockNotification(sbv0, n)); - F0->setKey(problem); + F0->link(problem); ASSERT_TRUE(problem->getStateBlockNotification(sbp0, n)); ASSERT_EQ(n, ADD); @@ -100,7 +85,7 @@ TEST_F(HasStateBlocksTest, Notifications_makeKF_add) // first make KF, then add SB // F1->link(problem->getTrajectory()); - F1->setKey(problem); + F1->link(problem); F1->addStateBlock('P', sbp1); @@ -131,7 +116,7 @@ TEST_F(HasStateBlocksTest, Add_solve_notify_solve_add) ASSERT_FALSE(problem->getStateBlockNotification(sbp0, n)); F0->addStateBlock('V', sbv0); - F0->setKey(problem); + F0->link(problem); ASSERT_TRUE(problem->getStateBlockNotification(sbv0, n)); ASSERT_EQ(n, ADD); diff --git a/test/gtest_odom_2d.cpp b/test/gtest_odom_2d.cpp index 3b525a12e5210de4eeb54ef213d8446bd24b8329..ab545f2eca3122493a20ac31024faab520f46c64 100644 --- a/test/gtest_odom_2d.cpp +++ b/test/gtest_odom_2d.cpp @@ -76,27 +76,24 @@ void show(const ProblemPtr& problem) for (FrameBasePtr F : *problem->getTrajectory()) { - if (F->isKey()) + cout << "----- Key Frame " << F->id() << " -----" << endl; + if (!F->getCaptureList().empty()) { - cout << "----- Key Frame " << F->id() << " -----" << endl; - if (!F->getCaptureList().empty()) + auto C = F->getCaptureList().front(); + if (!C->getFeatureList().empty()) { - auto C = F->getCaptureList().front(); - if (!C->getFeatureList().empty()) - { - auto f = C->getFeatureList().front(); - cout << " feature measure: \n" - << F->getCaptureList().front()->getFeatureList().front()->getMeasurement().transpose() - << endl; - cout << " feature covariance: \n" - << F->getCaptureList().front()->getFeatureList().front()->getMeasurementCovariance() << endl; - } + auto f = C->getFeatureList().front(); + cout << " feature measure: \n" + << F->getCaptureList().front()->getFeatureList().front()->getMeasurement().transpose() + << endl; + cout << " feature covariance: \n" + << F->getCaptureList().front()->getFeatureList().front()->getMeasurementCovariance() << endl; } - cout << " state: \n" << F->getStateVector().transpose() << endl; - Eigen::MatrixXd cov; - problem->getFrameCovariance(F,cov); - cout << " covariance: \n" << cov << endl; } + cout << " state: \n" << F->getStateVector().transpose() << endl; + Eigen::MatrixXd cov; + problem->getFrameCovariance(F,cov); + cout << " covariance: \n" << cov << endl; } } @@ -125,21 +122,21 @@ TEST(Odom2d, FactorFix_and_FactorOdom2d) Matrix3d delta_cov; delta_cov << .02, 0, 0, 0, .025, .02, 0, .02, .02; ProblemPtr Pr = Problem::create("PO", 2); - SolverCeres solver(Pr); + SolverCeres solver(Pr); // KF0 and absolute prior FrameBasePtr F0 = Pr->setPriorFactor(x0, s0,t0, dt/2); // KF1 and motion from KF0 t += dt; - FrameBasePtr F1 = Pr->emplaceKeyFrame(t, Vector3d::Zero()); + FrameBasePtr F1 = Pr->emplaceFrame(t, Vector3d::Zero()); auto C1 = CaptureBase::emplace<CaptureBase>(F1, "CaptureOdom2d", t); auto f1 = FeatureBase::emplace<FeatureBase>(C1, "FeatureOdom2d", delta, delta_cov); auto c1 = FactorBase::emplace<FactorOdom2d>(f1, f1, F0, nullptr, false); // KF2 and motion from KF1 t += dt; - FrameBasePtr F2 = Pr->emplaceKeyFrame(t, Vector3d::Zero()); + FrameBasePtr F2 = Pr->emplaceFrame(t, Vector3d::Zero()); auto C2 = CaptureBase::emplace<CaptureBase>(F2, "CaptureOdom2d", t); auto f2 = FeatureBase::emplace<FeatureBase>(C2, "FeatureOdom2d", delta, delta_cov); auto c2 = FactorBase::emplace<FactorOdom2d>(f2, f2, F1, nullptr, false); @@ -308,8 +305,6 @@ TEST(Odom2d, VoteForKfAndSolve) int n = 0; for (auto F : *problem->getTrajectory()) { - if (!F->isKey()) break; - ASSERT_POSE2d_APPROX(F->getStateVector("PO"), integrated_pose_vector[n] , 1e-6); ASSERT_TRUE (F->getCovariance(computed_cov)); ASSERT_MATRIX_APPROX(computed_cov , integrated_cov_vector[n] , 1e-6); @@ -423,7 +418,7 @@ TEST(Odom2d, KF_callback) std::cout << "-----------------------------\nSplit after last KF; time: " << t_split << std::endl; Vector3d x_split = processor_odom2d->getState(t_split).vector("PO"); - FrameBasePtr keyframe_2 = problem->emplaceKeyFrame(t_split, x_split); + FrameBasePtr keyframe_2 = problem->emplaceFrame(t_split, x_split); // there must be 2KF and one F ASSERT_EQ(problem->getTrajectory()->getFrameMap().size(), 2); @@ -460,7 +455,7 @@ TEST(Odom2d, KF_callback) problem->print(4,1,1,1); x_split = processor_odom2d->getState(t_split).vector("PO"); - FrameBasePtr keyframe_1 = problem->emplaceKeyFrame(t_split, x_split); + FrameBasePtr keyframe_1 = problem->emplaceFrame(t_split, x_split); ASSERT_TRUE(problem->check(0)); processor_odom2d->keyFrameCallback(keyframe_1, dt/2); diff --git a/test/gtest_pack_KF_buffer.cpp b/test/gtest_pack_KF_buffer.cpp index 056fbcf0bb231962e109ea60f404a5a0cefd58f5..d1fce41e50c72c91fb520d748a8154d5d516a1e6 100644 --- a/test/gtest_pack_KF_buffer.cpp +++ b/test/gtest_pack_KF_buffer.cpp @@ -34,10 +34,10 @@ class BufferPackKeyFrameTest : public testing::Test 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); - f21 = std::make_shared<FrameBase>(NON_ESTIMATED, TimeStamp(21),nullptr,nullptr,nullptr); - f28 = std::make_shared<FrameBase>(NON_ESTIMATED, TimeStamp(28),nullptr,nullptr,nullptr); + f10 = std::make_shared<FrameBase>(TimeStamp(10),nullptr,nullptr,nullptr); + f20 = std::make_shared<FrameBase>(TimeStamp(20),nullptr,nullptr,nullptr); + f21 = std::make_shared<FrameBase>(TimeStamp(21),nullptr,nullptr,nullptr); + f28 = std::make_shared<FrameBase>(TimeStamp(28),nullptr,nullptr,nullptr); tt10 = 1.0; tt20 = 1.0; @@ -230,7 +230,7 @@ TEST_F(BufferPackKeyFrameTest, removeUpTo) // Specifically, only f28 should remain pack_kf_buffer.add(f28, tt28); ASSERT_EQ(pack_kf_buffer.size(), (unsigned int) 2); - FrameBasePtr f22 = std::make_shared<FrameBase>(NON_ESTIMATED, TimeStamp(22),nullptr,nullptr,nullptr); + FrameBasePtr f22 = std::make_shared<FrameBase>(TimeStamp(22),nullptr,nullptr,nullptr); PackKeyFramePtr pack22 = std::make_shared<PackKeyFrame>(f22,5); pack_kf_buffer.removeUpTo( pack22->key_frame->getTimeStamp() ); ASSERT_EQ(pack_kf_buffer.size(), (unsigned int) 1); diff --git a/test/gtest_problem.cpp b/test/gtest_problem.cpp index dc44348f5943d7702372e28ebfb4e8ea2a707876..181fb1ce43bc80a8a04034191973d5ac60635b1e 100644 --- a/test/gtest_problem.cpp +++ b/test/gtest_problem.cpp @@ -224,9 +224,10 @@ TEST(Problem, emplaceFrame_factory) { ProblemPtr P = Problem::create("PO", 2); - FrameBasePtr f0 = P->emplaceKeyFrame(0, "PO" , 2, VectorXd(3) ); - FrameBasePtr f1 = P->emplaceKeyFrame(1, "PO" , 3, VectorXd(7) ); - FrameBasePtr f2 = P->emplaceKeyFrame(2, "POV", 3, VectorXd(10) ); + FrameBasePtr f0 = P->emplaceFrame(0, "PO" , 2, VectorXd(3) ); + FrameBasePtr f1 = P->emplaceFrame(1, "PO" , 3, VectorXd(7) ); + FrameBasePtr f2 = P->emplaceFrame(2, "POV", 3, VectorXd(10) ); + // check that all frames are effectively in the trajectory ASSERT_EQ(P->getTrajectory()->getFrameMap().size(), (SizeStd) 3); @@ -239,6 +240,8 @@ TEST(Problem, emplaceFrame_factory) ASSERT_EQ(f0->getProblem(), P); ASSERT_EQ(f1->getProblem(), P); ASSERT_EQ(f2->getProblem(), P); + + ASSERT_EQ(P->getFrameStructure(), "POV"); } TEST(Problem, StateBlocks) @@ -261,7 +264,7 @@ TEST(Problem, StateBlocks) auto pm = P->installProcessor("ProcessorOdom3d", "odom integrator", "odometer", wolf_root + "/test/yaml/processor_odom_3d.yaml"); // 2 state blocks, estimated - auto KF = P->emplaceKeyFrame(0, "PO", 3, xs3d ); + auto KF = P->emplaceFrame(0, "PO", 3, xs3d ); ASSERT_EQ(P->getStateBlockNotificationMapSize(), (SizeStd)(2 + 2)); // Notifications @@ -320,7 +323,7 @@ TEST(Problem, Covariances) // 4 state blocks, estimated St->unfixExtrinsics(); - FrameBasePtr F = P->emplaceKeyFrame(0, "PO", 3, xs3d ); + FrameBasePtr F = P->emplaceFrame(0, "PO", 3, xs3d ); // set covariance (they are not computed without a solver) P->addCovarianceBlock(F->getP(), Eigen::Matrix3d::Identity()); @@ -356,7 +359,7 @@ TEST(Problem, perturb) int i = 0; for (TimeStamp t = 0.0; t < 2.0; t += 1.0) { - auto F = problem->emplaceKeyFrame(t, pose ); + auto F = problem->emplaceFrame(t, pose ); if (i==0) F->fix(); for (int j = 0; j< 2 ; j++) @@ -385,21 +388,22 @@ TEST(Problem, perturb) //// CHECK ALL STATE BLOCKS /// - double prec = 1e-2; +#define prec 1e-2 for (auto S : problem->getHardware()->getSensorList()) { - ASSERT_TRUE (S->getP()->getState().isApprox(Vector2d(0,0), prec) ); - ASSERT_TRUE (S->getO()->getState().isApprox(Vector1d(0), prec) ); + ASSERT_MATRIX_APPROX(S->getP()->getState(), Vector2d(0,0), prec ); + ASSERT_MATRIX_APPROX(S->getO()->getState(), Vector1d(0), prec ); ASSERT_FALSE(S->getIntrinsic()->getState().isApprox(Vector3d(1,1,1), prec) ); } - for (auto F : *problem->getTrajectory()) + for (auto pair_T_F : problem->getTrajectory()->getFrameMap()) { + auto F = pair_T_F.second; if (F->isFixed()) // fixed { - ASSERT_TRUE (F->getP()->getState().isApprox(Vector2d(0,0), prec) ); - ASSERT_TRUE (F->getO()->getState().isApprox(Vector1d(0), prec) ); + ASSERT_MATRIX_APPROX (F->getP()->getState(), Vector2d(0,0), prec ); + ASSERT_MATRIX_APPROX (F->getO()->getState(), Vector1d(0), prec ); } else { @@ -416,8 +420,8 @@ TEST(Problem, perturb) { if ( L->isFixed() ) // fixed { - ASSERT_TRUE (L->getP()->getState().isApprox(Vector2d(1,2), prec) ); - ASSERT_TRUE (L->getO()->getState().isApprox(Vector1d(3), prec) ); + ASSERT_MATRIX_APPROX (L->getP()->getState(), Vector2d(1,2), prec ); + ASSERT_MATRIX_APPROX (L->getO()->getState(), Vector1d(3), prec ); } else { @@ -446,7 +450,7 @@ TEST(Problem, check) int i = 0; for (TimeStamp t = 0.0; t < 2.0; t += 1.0) { - auto F = problem->emplaceKeyFrame(t, pose); + auto F = problem->emplaceFrame(t, pose); if (i==0) F->fix(); for (int j = 0; j< 2 ; j++) @@ -564,6 +568,6 @@ TEST(Problem, getState) int main(int argc, char **argv) { testing::InitGoogleTest(&argc, argv); - //::testing::GTEST_FLAG(filter) = "Problem.getState"; +// ::testing::GTEST_FLAG(filter) = "Problem.emplaceFrame_factory"; return RUN_ALL_TESTS(); } diff --git a/test/gtest_processor_loopclosure.cpp b/test/gtest_processor_loopclosure.cpp index 6a4b40d32c0908484e31b576310657aba5d11fb4..4e50c870348da1877b3a599c48158730e2df47ab 100644 --- a/test/gtest_processor_loopclosure.cpp +++ b/test/gtest_processor_loopclosure.cpp @@ -35,10 +35,9 @@ protected: CaptureBasePtr findLoopCandidate(CaptureBasePtr _capture) override { for (FrameBasePtr kf : *getProblem()->getTrajectory()) - if (kf->isKey()) - for (CaptureBasePtr cap : kf->getCaptureList()) - if (cap != _capture) - return cap; + for (CaptureBasePtr cap : kf->getCaptureList()) + if (cap != _capture) + return cap; return nullptr; }; void emplaceFactors(CaptureBasePtr _capture_1, CaptureBasePtr _capture_2) override @@ -87,7 +86,7 @@ TEST(ProcessorLoopClosure, installProcessor) // new KF t += dt; - auto kf = problem->emplaceKeyFrame(t, x); //KF2 + auto kf = problem->emplaceFrame(t, x); //KF2 // emplace a capture in KF auto capt_lc = CaptureBase::emplace<CaptureVoid>(kf, t, sens_lc); proc_lc->captureCallback(capt_lc); diff --git a/test/gtest_processor_motion.cpp b/test/gtest_processor_motion.cpp index d905bcad555b88e4cd92afed94771c2e7f46546d..e531defd5721e3374308d67e793a01f682701577 100644 --- a/test/gtest_processor_motion.cpp +++ b/test/gtest_processor_motion.cpp @@ -312,7 +312,7 @@ TEST_F(ProcessorMotion_test, mergeCaptures) SensorBasePtr S = processor->getSensor(); TimeStamp t_target = 8.5; - FrameBasePtr F_target = problem->emplaceKeyFrame(t_target); + FrameBasePtr F_target = problem->emplaceFrame(t_target); CaptureMotionPtr C_source = std::dynamic_pointer_cast<CaptureMotion>(processor->getLast()); CaptureMotionPtr C_target = CaptureBase::emplace<CaptureMotion>(F_target, "ODOM 2d", @@ -389,7 +389,7 @@ TEST_F(ProcessorMotion_test, splitBufferAutoPrior) SensorBasePtr S = processor->getSensor(); TimeStamp t_target = 8.5; - FrameBasePtr F_target = problem->emplaceKeyFrame(t_target); + FrameBasePtr F_target = problem->emplaceFrame(t_target); CaptureMotionPtr C_source = std::dynamic_pointer_cast<CaptureMotion>(processor->getLast()); CaptureMotionPtr C_target = CaptureBase::emplace<CaptureMotion>(F_target, "ODOM 2d", @@ -434,7 +434,7 @@ TEST_F(ProcessorMotion_test, splitBufferFactorPrior) SensorBasePtr S = processor->getSensor(); TimeStamp t_target = 8.5; - FrameBasePtr F_target = problem->emplaceKeyFrame(t_target); + FrameBasePtr F_target = problem->emplaceFrame(t_target); CaptureMotionPtr C_source = std::dynamic_pointer_cast<CaptureMotion>(processor->getLast()); CaptureMotionPtr C_target = CaptureBase::emplace<CaptureMotion>(F_target, "ODOM 2d", @@ -479,7 +479,7 @@ TEST_F(ProcessorMotion_test, splitBufferFixPrior) SensorBasePtr S = processor->getSensor(); TimeStamp t_target = 8.5; - FrameBasePtr F_target = problem->emplaceKeyFrame(t_target); + FrameBasePtr F_target = problem->emplaceFrame(t_target); CaptureMotionPtr C_source = std::dynamic_pointer_cast<CaptureMotion>(processor->getLast()); CaptureMotionPtr C_target = CaptureBase::emplace<CaptureMotion>(F_target, "ODOM 2d", diff --git a/test/gtest_processor_tracker_feature_dummy.cpp b/test/gtest_processor_tracker_feature_dummy.cpp index 7b6dc1c40fe5a4eabcdeae278cd823fa01403fbb..49593d64afa531c28a8a490de0ba562ed1c13bb2 100644 --- a/test/gtest_processor_tracker_feature_dummy.cpp +++ b/test/gtest_processor_tracker_feature_dummy.cpp @@ -321,7 +321,6 @@ TEST_F(ProcessorTrackerFeatureDummyTest, process) CaptureBasePtr cap5 = std::make_shared<CaptureVoid>(4, sensor); cap5->process(); - ASSERT_TRUE(cap4->getFrame()->isKey()); ASSERT_EQ(problem->getTrajectory()->getLastFrame()->id(), cap4->getFrame()->id()); ASSERT_TRUE(problem->check(0)); diff --git a/test/gtest_solver_ceres_multithread.cpp b/test/gtest_solver_ceres_multithread.cpp index 91fa716cb45d02c14bf9dad6068c4d6f4bae6780..3cd41dde30bc72ecc16fc27d70b8cde5fe327a7b 100644 --- a/test/gtest_solver_ceres_multithread.cpp +++ b/test/gtest_solver_ceres_multithread.cpp @@ -56,7 +56,7 @@ TEST(SolverCeresMultithread, MultiThreadingTruncatedNotifications) while (true) { // Emplace Frame, Capture, feature and factor pose 2d - FrameBasePtr F = P->emplaceKeyFrame(ts, P->stateZero()); + FrameBasePtr F = P->emplaceFrame(ts, P->stateZero()); auto C = CaptureBase::emplace<CaptureVoid>(F, ts, nullptr); auto f = FeatureBase::emplace<FeatureBase>(C, "FeaturePose2d", Vector3d::Zero(), Matrix3d::Identity()); auto c = FactorBase::emplace<FactorPose2d>(f, f, nullptr, false); diff --git a/test/gtest_solver_manager_multithread.cpp b/test/gtest_solver_manager_multithread.cpp index 0770b33aed43e5ebbc9a204e68428f7a0022c870..4e772c1bb74747d80a6ceda04d62a679f323a4e3 100644 --- a/test/gtest_solver_manager_multithread.cpp +++ b/test/gtest_solver_manager_multithread.cpp @@ -51,7 +51,7 @@ TEST(SolverManagerMultithread, MultiThreadingTruncatedNotifications) while (true) { // Emplace Frame, Capture, feature and factor pose 2d - FrameBasePtr F = P->emplaceKeyFrame(ts, P->stateZero()); + FrameBasePtr F = P->emplaceFrame(ts, P->stateZero()); auto C = CaptureBase::emplace<CaptureVoid>(F, ts, nullptr); auto f = FeatureBase::emplace<FeatureBase>(C, "FeaturePose2d", Vector3d::Zero(), Matrix3d::Identity()); auto c = FactorBase::emplace<FactorPose2d>(f, f, nullptr, false); diff --git a/test/gtest_track_matrix.cpp b/test/gtest_track_matrix.cpp index 72bf3f7d8ce8124c4005daf4a9a82ba119504d5e..a14c436ddc0864f7b55e1ef9db1fd451ecf494ea 100644 --- a/test/gtest_track_matrix.cpp +++ b/test/gtest_track_matrix.cpp @@ -37,11 +37,11 @@ class TrackMatrixTest : public testing::Test // unlinked frames // Some warnings will be thrown "linking with nullptr" for emplacing without providing frame pointer - F0 = FrameBase::createNonKeyFrame<FrameBase>(0.0, nullptr); - F1 = FrameBase::createNonKeyFrame<FrameBase>(1.0, nullptr); - F2 = FrameBase::createNonKeyFrame<FrameBase>(2.0, nullptr); - F3 = FrameBase::createNonKeyFrame<FrameBase>(3.0, nullptr); - F4 = FrameBase::createNonKeyFrame<FrameBase>(4.0, nullptr); + F0 = std::make_shared<FrameBase>(0.0, nullptr); + F1 = std::make_shared<FrameBase>(1.0, nullptr); + F2 = std::make_shared<FrameBase>(2.0, nullptr); + F3 = std::make_shared<FrameBase>(3.0, nullptr); + F4 = std::make_shared<FrameBase>(4.0, nullptr); // unlinked features // Some warnings will be thrown "linking with nullptr" for emplacing without providing capture pointer @@ -52,8 +52,8 @@ class TrackMatrixTest : public testing::Test f4 = FeatureBase::emplace<FeatureBase>(nullptr, "FeatureBase", m, m_cov); // F0 and F4 are keyframes - F0->setKey(problem); - F4->setKey(problem); + F0->link(problem); + F4->link(problem); // link captures C0->link(F0); diff --git a/test/gtest_trajectory.cpp b/test/gtest_trajectory.cpp index ff103bc097ba9d166ef76a97fcde20b15199507a..bd05620f6fb13bdaa20a97343c12141f44d60c97 100644 --- a/test/gtest_trajectory.cpp +++ b/test/gtest_trajectory.cpp @@ -32,15 +32,15 @@ TEST(TrajectoryBase, ClosestKeyFrame) // 1 2 3 4 time stamps // --+-----+-----+-----+---> time - FrameBasePtr F1 = P->emplaceKeyFrame( 1, Eigen::Vector3d::Zero() ); - FrameBasePtr F2 = P->emplaceKeyFrame( 2, Eigen::Vector3d::Zero() ); + FrameBasePtr F1 = P->emplaceFrame( 1, Eigen::Vector3d::Zero() ); + FrameBasePtr F2 = P->emplaceFrame( 2, Eigen::Vector3d::Zero() ); // FrameBasePtr F3 = P->emplaceFrame(AUXILIARY, 3, Eigen::Vector3d::Zero() ); - FrameBasePtr F3 = FrameBase::createNonKeyFrame<FrameBase>(3, P->getFrameStructure(), -// P->getDim(), - std::list<VectorXd>({Eigen::Vector2d::Zero(),Eigen::Vector1d::Zero()}) ); - FrameBasePtr F4 = FrameBase::createNonKeyFrame<FrameBase>(4, P->getFrameStructure(), -// P->getDim(), - std::list<VectorXd>({Eigen::Vector2d::Zero(),Eigen::Vector1d::Zero()}) ); + FrameBasePtr F3 = std::make_shared<FrameBase>(3, P->getFrameStructure(), + // P->getDim(), + std::list<VectorXd>({Eigen::Vector2d::Zero(),Eigen::Vector1d::Zero()}) ); + FrameBasePtr F4 = std::make_shared<FrameBase>(4, P->getFrameStructure(), + // P->getDim(), + std::list<VectorXd>({Eigen::Vector2d::Zero(),Eigen::Vector1d::Zero()}) ); FrameBasePtr KF; // closest key-frame queried @@ -80,23 +80,23 @@ TEST(TrajectoryBase, Add_Remove_Frame) std::cout << __LINE__ << std::endl; // add F1 - FrameBasePtr F1 = P->emplaceKeyFrame(1, Eigen::Vector3d::Zero()); // 2 non-fixed + FrameBasePtr F1 = P->emplaceFrame(1, Eigen::Vector3d::Zero()); // 2 non-fixed if (debug) P->print(2,0,0,0); ASSERT_EQ(T->getFrameMap(). size(), (SizeStd) 1); ASSERT_EQ(P->getStateBlockNotificationMapSize(), (SizeStd) 2); std::cout << __LINE__ << std::endl; // add F2 - FrameBasePtr F2 = P->emplaceKeyFrame(2, Eigen::Vector3d::Zero()); // 1 fixed, 1 not + FrameBasePtr F2 = P->emplaceFrame(2, Eigen::Vector3d::Zero()); // 1 fixed, 1 not if (debug) P->print(2,0,0,0); ASSERT_EQ(T->getFrameMap(). size(), (SizeStd) 2); ASSERT_EQ(P->getStateBlockNotificationMapSize(), (SizeStd) 4); std::cout << __LINE__ << std::endl; // add F3 - FrameBasePtr F3 = FrameBase::createNonKeyFrame<FrameBase>(3, P->getFrameStructure(), -// P->getDim(), - std::list<VectorXd>({Eigen::Vector2d::Zero(),Eigen::Vector1d::Zero()})); + FrameBasePtr F3 = std::make_shared<FrameBase>(3, P->getFrameStructure(), + // P->getDim(), + std::list<VectorXd>({Eigen::Vector2d::Zero(),Eigen::Vector1d::Zero()})); if (debug) P->print(2,0,0,0); ASSERT_EQ(T->getFrameMap(). size(), (SizeStd) 2); ASSERT_EQ(P->getStateBlockNotificationMapSize(), (SizeStd) 4); diff --git a/test/gtest_tree_manager.cpp b/test/gtest_tree_manager.cpp index 15bb1778940d6e2d1e80ad05e195caba66b6417d..9c684c7bc0f3f30199a8d86e2ca9bf4b8aacb87f 100644 --- a/test/gtest_tree_manager.cpp +++ b/test/gtest_tree_manager.cpp @@ -94,7 +94,7 @@ TEST(TreeManager, keyFrameCallback) ASSERT_EQ(GM->n_KF_, 0); - auto F0 = P->emplaceKeyFrame(0, "PO", 3, VectorXd(7) ); + auto F0 = P->emplaceFrame(0, "PO", 3, VectorXd(7) ); P->keyFrameCallback(F0, nullptr, 0); ASSERT_EQ(GM->n_KF_, 1); diff --git a/test/gtest_tree_manager_sliding_window.cpp b/test/gtest_tree_manager_sliding_window.cpp index 0c5e7c2aec97277425289f3f28a9ba3d61dece1c..e8ffeb407df4df15c00715b21a3e86d554b38da8 100644 --- a/test/gtest_tree_manager_sliding_window.cpp +++ b/test/gtest_tree_manager_sliding_window.cpp @@ -87,7 +87,7 @@ TEST(TreeManagerSlidingWindow, slidingWindowFixViral) Matrix6d cov = Matrix6d::Identity(); // FRAME 2 ---------------------------------------------------------- - auto F2 = P->emplaceKeyFrame(TimeStamp(2), "PO", 3, state); + auto F2 = P->emplaceFrame(TimeStamp(2), "PO", 3, state); P->keyFrameCallback(F2, nullptr, 0); // absolute factor @@ -103,7 +103,7 @@ TEST(TreeManagerSlidingWindow, slidingWindowFixViral) EXPECT_FALSE(F1->isRemoving()); // FRAME 3 ---------------------------------------------------------- - auto F3 = P->emplaceKeyFrame(TimeStamp(3), "PO", 3, state); + auto F3 = P->emplaceFrame(TimeStamp(3), "PO", 3, state); P->keyFrameCallback(F3, nullptr, 0); // absolute factor @@ -119,7 +119,7 @@ TEST(TreeManagerSlidingWindow, slidingWindowFixViral) EXPECT_FALSE(F1->isRemoving()); // FRAME 4 ---------------------------------------------------------- - auto F4 = P->emplaceKeyFrame(TimeStamp(4), "PO", 3, state); + auto F4 = P->emplaceFrame(TimeStamp(4), "PO", 3, state); P->keyFrameCallback(F4, nullptr, 0); // absolute factor @@ -139,7 +139,7 @@ TEST(TreeManagerSlidingWindow, slidingWindowFixViral) EXPECT_TRUE(F2->isFixed()); //Fixed // FRAME 5 ---------------------------------------------------------- - auto F5 = P->emplaceKeyFrame(TimeStamp(5), "PO", 3, state); + auto F5 = P->emplaceFrame(TimeStamp(5), "PO", 3, state); P->keyFrameCallback(F5, nullptr, 0); // absolute factor @@ -184,7 +184,7 @@ TEST(TreeManagerSlidingWindow, slidingWindowNoFixNoViral) Matrix6d cov = Matrix6d::Identity(); // FRAME 2 ---------------------------------------------------------- - auto F2 = P->emplaceKeyFrame(TimeStamp(2), "PO", 3, state); + auto F2 = P->emplaceFrame(TimeStamp(2), "PO", 3, state); P->keyFrameCallback(F2, nullptr, 0); // absolute factor @@ -200,7 +200,7 @@ TEST(TreeManagerSlidingWindow, slidingWindowNoFixNoViral) EXPECT_FALSE(F1->isRemoving()); // FRAME 3 ---------------------------------------------------------- - auto F3 = P->emplaceKeyFrame(TimeStamp(3), "PO", 3, state); + auto F3 = P->emplaceFrame(TimeStamp(3), "PO", 3, state); P->keyFrameCallback(F3, nullptr, 0); // absolute factor @@ -216,7 +216,7 @@ TEST(TreeManagerSlidingWindow, slidingWindowNoFixNoViral) EXPECT_FALSE(F1->isRemoving()); // FRAME 4 ---------------------------------------------------------- - auto F4 = P->emplaceKeyFrame(TimeStamp(4), "PO", 3, state); + auto F4 = P->emplaceFrame(TimeStamp(4), "PO", 3, state); P->keyFrameCallback(F4, nullptr, 0); // absolute factor @@ -236,7 +236,7 @@ TEST(TreeManagerSlidingWindow, slidingWindowNoFixNoViral) EXPECT_FALSE(F2->isFixed()); //Not fixed // FRAME 5 ---------------------------------------------------------- - auto F5 = P->emplaceKeyFrame(TimeStamp(5), "PO", 3, state); + auto F5 = P->emplaceFrame(TimeStamp(5), "PO", 3, state); P->keyFrameCallback(F5, nullptr, 0); // absolute factor diff --git a/test/gtest_tree_manager_sliding_window_dual_rate.cpp b/test/gtest_tree_manager_sliding_window_dual_rate.cpp index ae4112bc3c27d88e103694ffd0824f4b7b35de2d..fa1414aafe81283cbc931b20498e3b737b13b533 100644 --- a/test/gtest_tree_manager_sliding_window_dual_rate.cpp +++ b/test/gtest_tree_manager_sliding_window_dual_rate.cpp @@ -117,7 +117,7 @@ TEST(TreeManagerSlidingWindowDualRate, slidingWindowFixViral) * Sliding window: * ( ) ( ) ( )(F1)(F2) */ - auto F2 = P->emplaceKeyFrame(TimeStamp(2), "PO", 3, state); + auto F2 = P->emplaceFrame(TimeStamp(2), "PO", 3, state); P->keyFrameCallback(F2, nullptr, 0); // absolute factor @@ -151,7 +151,7 @@ TEST(TreeManagerSlidingWindowDualRate, slidingWindowFixViral) * Sliding window: * ( ) ( ) (F1)(F2)(F3) */ - auto F3 = P->emplaceKeyFrame(TimeStamp(3), "PO", 3, state); + auto F3 = P->emplaceFrame(TimeStamp(3), "PO", 3, state); P->keyFrameCallback(F3, nullptr, 0); // absolute factor @@ -194,7 +194,7 @@ TEST(TreeManagerSlidingWindowDualRate, slidingWindowFixViral) * Sliding window: * ( ) (F1)(F2)(F3)(F4) */ - auto F4 = P->emplaceKeyFrame(TimeStamp(4), "PO", 3, state); + auto F4 = P->emplaceFrame(TimeStamp(4), "PO", 3, state); P->keyFrameCallback(F4, nullptr, 0); // absolute factor @@ -246,7 +246,7 @@ TEST(TreeManagerSlidingWindowDualRate, slidingWindowFixViral) * Sliding window: * ( ) (F1) (F3)(F4)(F5) */ - auto F5 = P->emplaceKeyFrame(TimeStamp(5), "PO", 3, state); + auto F5 = P->emplaceFrame(TimeStamp(5), "PO", 3, state); P->keyFrameCallback(F5, nullptr, 0); // absolute factor @@ -306,7 +306,7 @@ TEST(TreeManagerSlidingWindowDualRate, slidingWindowFixViral) * Sliding window: * (F1) (F3)(F4)(F5)(F6) */ - auto F6 = P->emplaceKeyFrame(TimeStamp(6), "PO", 3, state); + auto F6 = P->emplaceFrame(TimeStamp(6), "PO", 3, state); P->keyFrameCallback(F6, nullptr, 0); // absolute factor @@ -375,7 +375,7 @@ TEST(TreeManagerSlidingWindowDualRate, slidingWindowFixViral) * Sliding window: * (F1) (F3) (F5)(F6)(F7) */ - auto F7 = P->emplaceKeyFrame(TimeStamp(7), "PO", 3, state); + auto F7 = P->emplaceFrame(TimeStamp(7), "PO", 3, state); P->keyFrameCallback(F7, nullptr, 0); // absolute factor @@ -452,7 +452,7 @@ TEST(TreeManagerSlidingWindowDualRate, slidingWindowFixViral) * Sliding window: * (F3) (F5)(F6)(F7)(F8) */ - auto F8 = P->emplaceKeyFrame(TimeStamp(8), "PO", 3, state); + auto F8 = P->emplaceFrame(TimeStamp(8), "PO", 3, state); P->keyFrameCallback(F8, nullptr, 0); // absolute factor @@ -578,7 +578,7 @@ TEST(TreeManagerSlidingWindowDualRate, slidingWindowNoFixNoViral) * Sliding window: * ( ) ( ) ( )(F1)(F2) */ - auto F2 = P->emplaceKeyFrame(TimeStamp(2), "PO", 3, state); + auto F2 = P->emplaceFrame(TimeStamp(2), "PO", 3, state); P->keyFrameCallback(F2, nullptr, 0); // absolute factor @@ -612,7 +612,7 @@ TEST(TreeManagerSlidingWindowDualRate, slidingWindowNoFixNoViral) * Sliding window: * ( ) ( ) (F1)(F2)(F3) */ - auto F3 = P->emplaceKeyFrame(TimeStamp(3), "PO", 3, state); + auto F3 = P->emplaceFrame(TimeStamp(3), "PO", 3, state); P->keyFrameCallback(F3, nullptr, 0); // absolute factor @@ -655,7 +655,7 @@ TEST(TreeManagerSlidingWindowDualRate, slidingWindowNoFixNoViral) * Sliding window: * ( ) (F1)(F2)(F3)(F4) */ - auto F4 = P->emplaceKeyFrame(TimeStamp(4), "PO", 3, state); + auto F4 = P->emplaceFrame(TimeStamp(4), "PO", 3, state); P->keyFrameCallback(F4, nullptr, 0); // absolute factor @@ -707,7 +707,7 @@ TEST(TreeManagerSlidingWindowDualRate, slidingWindowNoFixNoViral) * Sliding window: * ( ) (F1) (F3)(F4)(F5) */ - auto F5 = P->emplaceKeyFrame(TimeStamp(5), "PO", 3, state); + auto F5 = P->emplaceFrame(TimeStamp(5), "PO", 3, state); P->keyFrameCallback(F5, nullptr, 0); // absolute factor @@ -767,7 +767,7 @@ TEST(TreeManagerSlidingWindowDualRate, slidingWindowNoFixNoViral) * Sliding window: * (F1) (F3)(F4)(F5)(F6) */ - auto F6 = P->emplaceKeyFrame(TimeStamp(6), "PO", 3, state); + auto F6 = P->emplaceFrame(TimeStamp(6), "PO", 3, state); P->keyFrameCallback(F6, nullptr, 0); // absolute factor @@ -836,7 +836,7 @@ TEST(TreeManagerSlidingWindowDualRate, slidingWindowNoFixNoViral) * Sliding window: * (F1) (F3) (F5)(F6)(F7) */ - auto F7 = P->emplaceKeyFrame(TimeStamp(7), "PO", 3, state); + auto F7 = P->emplaceFrame(TimeStamp(7), "PO", 3, state); P->keyFrameCallback(F7, nullptr, 0); // absolute factor @@ -913,7 +913,7 @@ TEST(TreeManagerSlidingWindowDualRate, slidingWindowNoFixNoViral) * Sliding window: * (F3) (F5)(F6)(F7)(F8) */ - auto F8 = P->emplaceKeyFrame(TimeStamp(8), "PO", 3, state); + auto F8 = P->emplaceFrame(TimeStamp(8), "PO", 3, state); P->keyFrameCallback(F8, nullptr, 0); // absolute factor