From e1087315cfce02a119be3f514c74d88dc2e4554f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Sol=C3=A0?= <jsola@iri.upc.edu> Date: Fri, 18 Dec 2020 17:00:33 +0100 Subject: [PATCH] Rename emplaceKeyFrame --> emplaceFrame --- include/core/frame/frame_base.h | 4 +- include/core/problem/problem.h | 30 +++-------- src/problem/problem.cpp | 51 +++++-------------- src/processor/processor_motion.cpp | 2 +- src/processor/processor_tracker.cpp | 2 +- test/gtest_emplace.cpp | 12 ++--- test/gtest_factor_absolute.cpp | 2 +- test/gtest_factor_autodiff.cpp | 16 +++--- test/gtest_factor_autodiff_distance_3d.cpp | 4 +- test/gtest_factor_block_difference.cpp | 2 +- test/gtest_factor_diff_drive.cpp | 4 +- test/gtest_factor_odom_2d.cpp | 4 +- test/gtest_factor_odom_3d.cpp | 4 +- test/gtest_factor_pose_2d.cpp | 2 +- test/gtest_factor_pose_3d.cpp | 2 +- test/gtest_factor_relative_2d_analytic.cpp | 4 +- ...actor_relative_pose_2d_with_extrinsics.cpp | 4 +- test/gtest_frame_base.cpp | 4 +- test/gtest_odom_2d.cpp | 8 +-- test/gtest_problem.cpp | 14 ++--- test/gtest_processor_loopclosure.cpp | 2 +- test/gtest_processor_motion.cpp | 8 +-- test/gtest_solver_ceres_multithread.cpp | 2 +- test/gtest_solver_manager_multithread.cpp | 2 +- test/gtest_trajectory.cpp | 8 +-- test/gtest_tree_manager.cpp | 2 +- test/gtest_tree_manager_sliding_window.cpp | 16 +++--- ..._tree_manager_sliding_window_dual_rate.cpp | 28 +++++----- 28 files changed, 100 insertions(+), 143 deletions(-) diff --git a/include/core/frame/frame_base.h b/include/core/frame/frame_base.h index a9d1d0e26..731bf8db5 100644 --- a/include/core/frame/frame_base.h +++ b/include/core/frame/frame_base.h @@ -125,7 +125,7 @@ class FrameBase : public NodeBase, public HasStateBlocks, public std::enable_sha bool isConstrainedBy(const FactorBasePtr& _factor) const; void link(TrajectoryBasePtr); template<typename classType, typename... T> - static std::shared_ptr<classType> emplaceKeyFrame(TrajectoryBasePtr _ptr, T&&... all); + static std::shared_ptr<classType> emplaceFrame(TrajectoryBasePtr _ptr, T&&... all); template<typename classType, typename... T> static std::shared_ptr<classType> createNonKeyFrame(T&&... all); @@ -168,7 +168,7 @@ 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::emplaceFrame(TrajectoryBasePtr _ptr, T&&... all) { std::shared_ptr<classType> frm = std::make_shared<classType>(std::forward<T>(all)...); frm->link(_ptr); diff --git a/include/core/problem/problem.h b/include/core/problem/problem.h index 9b86ec2fb..44e2fe69e 100644 --- a/include/core/problem/problem.h +++ b/include/core/problem/problem.h @@ -217,7 +217,7 @@ 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); @@ -235,7 +235,7 @@ 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); @@ -252,7 +252,7 @@ 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 @@ -269,7 +269,7 @@ 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); @@ -286,7 +286,7 @@ 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 @@ -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/src/problem/problem.cpp b/src/problem/problem.cpp index f97b97d73..b574f7ac1 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) @@ -352,53 +352,53 @@ FrameBasePtr Problem::emplaceKeyFrame(const TimeStamp& _time_stamp, // assert (_frame_state.size() == index && "State vector incompatible with given structure and dimension! Vector too large."); - auto frm = FrameBase::emplaceKeyFrame<FrameBase>(trajectory_ptr_, + auto frm = FrameBase::emplaceFrame<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, + return emplaceFrame(_time_stamp, _frame_structure, getState(_time_stamp)); } -FrameBasePtr Problem::emplaceKeyFrame (const TimeStamp& _time_stamp, // +FrameBasePtr Problem::emplaceFrame (const TimeStamp& _time_stamp, // const StateStructure& _frame_structure, // const VectorComposite& _frame_state) { - return FrameBase::emplaceKeyFrame<FrameBase>(getTrajectory(), + return FrameBase::emplaceFrame<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(), + return FrameBase::emplaceFrame<FrameBase>(getTrajectory(), _time_stamp, getFrameStructure(), _frame_state); } -FrameBasePtr Problem::emplaceKeyFrame(const TimeStamp& _time_stamp, // +FrameBasePtr Problem::emplaceFrame(const TimeStamp& _time_stamp, // const Eigen::VectorXd& _frame_state) { - return emplaceKeyFrame(_time_stamp, + 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, + return emplaceFrame(_time_stamp, this->getFrameStructure(), this->getDim()); } @@ -639,31 +639,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 +986,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") diff --git a/src/processor/processor_motion.cpp b/src/processor/processor_motion.cpp index 4d06c1d75..a4ef91f15 100644 --- a/src/processor/processor_motion.cpp +++ b/src/processor/processor_motion.cpp @@ -662,7 +662,7 @@ 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(), + FrameBasePtr key_frame_ptr = FrameBase::emplaceFrame<FrameBase>(getProblem()->getTrajectory(), _ts_origin, getStateStructure(), _x_origin); diff --git a/src/processor/processor_tracker.cpp b/src/processor/processor_tracker.cpp index a52071c23..1a6e53d7e 100644 --- a/src/processor/processor_tracker.cpp +++ b/src/processor/processor_tracker.cpp @@ -81,7 +81,7 @@ void ProcessorTracker::processCapture(CaptureBasePtr _incoming_ptr) { WOLF_DEBUG( "PT ", getName(), " FIRST_TIME_WITHOUT_PACK" ); - FrameBasePtr kfrm = FrameBase::emplaceKeyFrame<FrameBase>(getProblem()->getTrajectory(), + FrameBasePtr kfrm = FrameBase::emplaceFrame<FrameBase>(getProblem()->getTrajectory(), incoming_ptr_->getTimeStamp(), getProblem()->getFrameStructure(), getProblem()->getState()); diff --git a/test/gtest_emplace.cpp b/test/gtest_emplace.cpp index ebca6bb09..23d0e0970 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::emplaceFrame<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::emplaceFrame<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::emplaceFrame<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::emplaceFrame<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::emplaceFrame<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::emplaceFrame<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 8c3b353cc..dc3551d2c 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 9f67d98ab..f4e3108d6 100644 --- a/test/gtest_factor_autodiff.cpp +++ b/test/gtest_factor_autodiff.cpp @@ -353,8 +353,8 @@ TEST(FactorAutodiff, EmplaceOdom2d) ProblemPtr problem = Problem::create("PO", 2); - FrameBasePtr fr1_ptr = problem->emplaceKeyFrame(TimeStamp(1)); - FrameBasePtr fr2_ptr = problem->emplaceKeyFrame(TimeStamp(2)); + FrameBasePtr fr1_ptr = problem->emplaceFrame(TimeStamp(1)); + FrameBasePtr fr2_ptr = problem->emplaceFrame(TimeStamp(2)); // SENSOR ParamsSensorOdom2d intrinsics_odo; @@ -386,8 +386,8 @@ TEST(FactorAutodiff, ResidualOdom2d) f1_pose << 2,1,M_PI; f2_pose << 3,5,3*M_PI/2; - FrameBasePtr fr1_ptr = problem->emplaceKeyFrame(TimeStamp(1), f1_pose); - FrameBasePtr fr2_ptr = problem->emplaceKeyFrame(TimeStamp(2), f2_pose); + FrameBasePtr fr1_ptr = problem->emplaceFrame(TimeStamp(1), f1_pose); + FrameBasePtr fr2_ptr = problem->emplaceFrame(TimeStamp(2), f2_pose); // SENSOR ParamsSensorOdom2d intrinsics_odo; @@ -432,8 +432,8 @@ TEST(FactorAutodiff, JacobianOdom2d) f1_pose << 2,1,M_PI; f2_pose << 3,5,3*M_PI/2; - FrameBasePtr fr1_ptr = problem->emplaceKeyFrame(TimeStamp(1), f1_pose); - FrameBasePtr fr2_ptr = problem->emplaceKeyFrame(TimeStamp(2), f2_pose); + FrameBasePtr fr1_ptr = problem->emplaceFrame(TimeStamp(1), f1_pose); + FrameBasePtr fr2_ptr = problem->emplaceFrame(TimeStamp(2), f2_pose); // SENSOR ParamsSensorOdom2d intrinsics_odo; @@ -512,8 +512,8 @@ TEST(FactorAutodiff, AutodiffVsAnalytic) f1_pose << 2,1,M_PI; f2_pose << 3,5,3*M_PI/2; - FrameBasePtr fr1_ptr = problem->emplaceKeyFrame(TimeStamp(1), f1_pose); - FrameBasePtr fr2_ptr = problem->emplaceKeyFrame(TimeStamp(2), f2_pose); + 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 3e6974cb9..fa3d36542 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_block_difference.cpp b/test/gtest_factor_block_difference.cpp index 9b572504f..1dbf21b97 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 51661f8ab..61f38c020 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::emplaceFrame<FrameBase>(trajectory, 0.0, "PO", std::list<VectorXd>{Vector2d(0,0), Vector1d(0)}); - F1 = FrameBase::emplaceKeyFrame<FrameBase>(trajectory, + F1 = FrameBase::emplaceFrame<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 baee1dddc..740933a67 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 24daac332..7a57f0354 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 749d514d8..7ecc6ab08 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 88433b4b4..c44374caa 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 93581a6ac..70cbc4647 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 78321478c..0b8c4a8a3 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); diff --git a/test/gtest_frame_base.cpp b/test/gtest_frame_base.cpp index 956567ee8..8b651ae32 100644 --- a/test/gtest_frame_base.cpp +++ b/test/gtest_frame_base.cpp @@ -65,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::emplaceFrame<FrameBase>(T, 1, make_shared<StateBlock>(2), make_shared<StateBlock>(1)); + auto F2 = FrameBase::emplaceFrame<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>()); diff --git a/test/gtest_odom_2d.cpp b/test/gtest_odom_2d.cpp index c4b9d0979..ab545f2ec 100644 --- a/test/gtest_odom_2d.cpp +++ b/test/gtest_odom_2d.cpp @@ -129,14 +129,14 @@ TEST(Odom2d, FactorFix_and_FactorOdom2d) // 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); @@ -418,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); @@ -455,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_problem.cpp b/test/gtest_problem.cpp index a0b8971db..f40f2f44f 100644 --- a/test/gtest_problem.cpp +++ b/test/gtest_problem.cpp @@ -224,9 +224,9 @@ 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); @@ -261,7 +261,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 +320,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 +356,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++) @@ -447,7 +447,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++) diff --git a/test/gtest_processor_loopclosure.cpp b/test/gtest_processor_loopclosure.cpp index 7f99374f5..4e50c8703 100644 --- a/test/gtest_processor_loopclosure.cpp +++ b/test/gtest_processor_loopclosure.cpp @@ -86,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 d905bcad5..e531defd5 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_solver_ceres_multithread.cpp b/test/gtest_solver_ceres_multithread.cpp index 91fa716cb..3cd41dde3 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 0770b33ae..4e772c1bb 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_trajectory.cpp b/test/gtest_trajectory.cpp index ff103bc09..81f09e4e5 100644 --- a/test/gtest_trajectory.cpp +++ b/test/gtest_trajectory.cpp @@ -32,8 +32,8 @@ 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(), @@ -80,14 +80,14 @@ 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); diff --git a/test/gtest_tree_manager.cpp b/test/gtest_tree_manager.cpp index 15bb17789..9c684c7bc 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 0c5e7c2ae..e8ffeb407 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 ae4112bc3..fa1414aaf 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 -- GitLab