From 1f96e1a7f0c8c91cadadafadea21afce1400e285 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?M=C3=A9d=C3=A9ric=20Fourmy?= <mfourmy@laas.fr>
Date: Wed, 18 Mar 2020 20:24:13 +0100
Subject: [PATCH] Adapting core to the use of multiple processor motion, gtest

---
 include/core/problem/problem.h            |  30 +++--
 include/core/processor/is_motion.h        |   6 +
 include/core/processor/processor_motion.h |   2 +-
 src/frame/frame_base.cpp                  |  22 +++-
 src/problem/problem.cpp                   | 146 +++++++++++-----------
 src/processor/processor_base.cpp          |  44 +++----
 src/processor/processor_motion.cpp        |  20 ++-
 test/gtest_problem.cpp                    |  10 +-
 8 files changed, 150 insertions(+), 130 deletions(-)

diff --git a/include/core/problem/problem.h b/include/core/problem/problem.h
index 8e5c10205..9da4d31f5 100644
--- a/include/core/problem/problem.h
+++ b/include/core/problem/problem.h
@@ -46,8 +46,7 @@ class Problem : public std::enable_shared_from_this<Problem>
         HardwareBasePtr     hardware_ptr_;
         TrajectoryBasePtr   trajectory_ptr_;
         MapBasePtr          map_ptr_;
-        std::vector<IsMotionPtr>  processor_is_motion_vec_;
-//        IsMotionPtr         is_motion_ptr_;
+        std::list<IsMotionPtr>  processor_is_motion_list_;
         std::map<std::pair<StateBlockPtr, StateBlockPtr>, Eigen::MatrixXd> covariances_;
         SizeEigen state_size_, state_cov_size_, dim_;
         std::map<FactorBasePtr, Notification> factor_notification_map_;
@@ -151,11 +150,12 @@ class Problem : public std::enable_shared_from_this<Problem>
          */
         void addProcessorMotion(IsMotionPtr _processor_motion_ptr);
         IsMotionPtr addProcessorMotion(const std::string& _unique_processor_name);
-        void clearProcessorMotion();
+        void clearProcessorIsMotion(IsMotionPtr proc);
 
     public:
-        IsMotionPtr& getProcessorMotion();
-
+        IsMotionPtr getProcessorIsMotion();
+        std::list<IsMotionPtr> getProcessorIsMotionList();
+        
         // Trajectory branch ----------------------------------
         TrajectoryBasePtr getTrajectory() const;
         virtual FrameBasePtr setPrior(const Eigen::VectorXd& _prior_state, //
@@ -362,18 +362,26 @@ inline bool Problem::priorIsSet() const
     return prior_is_set_;
 }
 
-inline IsMotionPtr& Problem::getProcessorMotion()
+inline IsMotionPtr Problem::getProcessorIsMotion()
 {
-    if (!processor_is_motion_vec_.empty())
-        return processor_is_motion_vec_[0];
-    return nullptr
+    if (!processor_is_motion_list_.empty())
+        return processor_is_motion_list_.front();
+    return nullptr;
 }
 
-inline IsMotionPtr& Problem::getIsMotionVector()
+inline std::list<IsMotionPtr> Problem::getProcessorIsMotionList()
 {
-    return processor_is_motion_vec_;
+    return processor_is_motion_list_;
 }
 
+// linking error -> TODO
+// void Problem::clearProcessorIsMotion(IsMotionPtr proc){
+//     auto it = std::find(processor_is_motion_list_.begin(), processor_is_motion_list_.end(), proc);
+//     if (it != processor_is_motion_list_.end()){
+//         processor_is_motion_list_.erase(it);
+//     }
+// }
+
 inline std::map<StateBlockPtr,Notification> Problem::consumeStateBlockNotificationMap()
 {
     std::lock_guard<std::mutex> lock(mut_state_block_notifications_);
diff --git a/include/core/processor/is_motion.h b/include/core/processor/is_motion.h
index e749ec214..842a8c63c 100644
--- a/include/core/processor/is_motion.h
+++ b/include/core/processor/is_motion.h
@@ -50,6 +50,12 @@ class IsMotion
          */
         virtual Eigen::VectorXd getState(const TimeStamp& _ts) const = 0;
 
+        std::string getStateStructure(){return state_structure_;};
+        void setStateStructure(std::string _state_structure){state_structure_ = _state_structure;};
+    
+    protected:
+        std::string state_structure_; ///< The structure of the state vector (to retrieve state blocks from frames)
+
 };
 
 }
diff --git a/include/core/processor/processor_motion.h b/include/core/processor/processor_motion.h
index 57c164469..29712b931 100644
--- a/include/core/processor/processor_motion.h
+++ b/include/core/processor/processor_motion.h
@@ -509,7 +509,7 @@ inline bool ProcessorMotion::voteForKeyFrame() const
 
 inline Eigen::VectorXd ProcessorMotion::getState(const TimeStamp& _ts) const
 {
-    Eigen::VectorXd x(getProblem()->getFrameStructureSize());
+    Eigen::VectorXd x(getProblem()->getFrameStructureSize());  // TODO -> wrong
     getState(_ts, x);
     return x;
 }
diff --git a/src/frame/frame_base.cpp b/src/frame/frame_base.cpp
index ca5918624..d437515e4 100644
--- a/src/frame/frame_base.cpp
+++ b/src/frame/frame_base.cpp
@@ -64,14 +64,14 @@ FrameBase::FrameBase(const std::string _frame_structure, const SizeEigen _dim, c
            time_stamp_(_ts)
 {
     if(_frame_structure.compare("PO") == 0 and _dim == 2){
-        assert(_x.size() == 3 && "Wrong state vector size. Should be 3 for 2D!");
+        assert(_x.size() == 3 && "Wrong state vector size. Should be 3 for PO 2D!");
         StateBlockPtr p_ptr ( std::make_shared<StateBlock>    (_x.head    <2> ( ) ) );
         StateBlockPtr o_ptr ( std::make_shared<StateAngle>    ((double) _x(2) ) );
         addStateBlock("P", p_ptr);
         addStateBlock("O", o_ptr);
         this->setType("PO 2D");
     }else if(_frame_structure.compare("PO") == 0 and _dim == 3){
-        assert(_x.size() == 7 && "Wrong state vector size. Should be 7 for 3D!");
+        assert(_x.size() == 7 && "Wrong state vector size. Should be 7 for PO 3D!");
         StateBlockPtr p_ptr ( std::make_shared<StateBlock>      (_x.head    <3> ( ) ) );
         StateBlockPtr o_ptr ( std::make_shared<StateQuaternion> (_x.tail    <4> ( ) ) );
         addStateBlock("P", p_ptr);
@@ -79,7 +79,7 @@ FrameBase::FrameBase(const std::string _frame_structure, const SizeEigen _dim, c
         this->setType("PO 3D");
     }else if(_frame_structure.compare("POV") == 0 and _dim == 3){
         // auto _x = Eigen::VectorXd::Zero(10);
-        assert(_x.size() == 10 && "Wrong state vector size. Should be 10 for 3D!");
+        assert(_x.size() == 10 && "Wrong state vector size. Should be 10 for POV 3D!");
         StateBlockPtr p_ptr ( std::make_shared<StateBlock>      (_x.head    <3> ( ) ) );
         StateBlockPtr o_ptr ( std::make_shared<StateQuaternion> (_x.segment <4> (3) ) );
         StateBlockPtr v_ptr ( std::make_shared<StateBlock>      (_x.tail    <3> ( ) ) );
@@ -87,6 +87,22 @@ FrameBase::FrameBase(const std::string _frame_structure, const SizeEigen _dim, c
         addStateBlock("O", o_ptr);
         addStateBlock("V", v_ptr);
         this->setType("POV 3D");
+    }else if(_frame_structure.compare("POVCDL") == 0 and _dim == 3){
+        // auto _x = Eigen::VectorXd::Zero(10);
+        assert(_x.size() == 19 && "Wrong state vector size. Should be 19 for POVCDL 3D!");
+        StateBlockPtr p_ptr ( std::make_shared<StateBlock>      (_x.head    <3> (  ) ) );
+        StateBlockPtr o_ptr ( std::make_shared<StateQuaternion> (_x.segment <4> (3 ) ) );
+        StateBlockPtr v_ptr ( std::make_shared<StateBlock>      (_x.segment <3> (7 ) ) );
+        StateBlockPtr c_ptr ( std::make_shared<StateBlock>      (_x.segment <3> (10) ) );
+        StateBlockPtr cd_ptr ( std::make_shared<StateBlock>      (_x.segment <3> (13) ) );
+        StateBlockPtr Lc_ptr ( std::make_shared<StateBlock>      (_x.segment <3> (16) ) );
+        addStateBlock("P", p_ptr);
+        addStateBlock("O", o_ptr);
+        addStateBlock("V", v_ptr);
+        addStateBlock("C", c_ptr);
+        addStateBlock("D", cd_ptr);
+        addStateBlock("L", Lc_ptr);
+        this->setType("POVCDL 3D");
     }else{
         std::cout << _frame_structure << " ^^ " << _dim << std::endl;
         throw std::runtime_error("Unknown frame structure");
diff --git a/src/problem/problem.cpp b/src/problem/problem.cpp
index 5b741765d..ff5729536 100644
--- a/src/problem/problem.cpp
+++ b/src/problem/problem.cpp
@@ -34,25 +34,27 @@ Problem::Problem(const std::string& _frame_structure, SizeEigen _dim) :
         hardware_ptr_(std::make_shared<HardwareBase>()),
         trajectory_ptr_(std::make_shared<TrajectoryBase>(_frame_structure)),
         map_ptr_(std::make_shared<MapBase>()),
-        processor_is_motion_vec_(std::vector<IsMotionPtr>()),
+        processor_is_motion_list_(std::list<IsMotionPtr>()),
         prior_is_set_(false),
         frame_structure_(_frame_structure)
 {
+    dim_ = _dim;
     if (_frame_structure == "PO" and _dim == 2)
     {
         state_size_ = 3;
         state_cov_size_ = 3;
-        dim_ = 2;
     }else if (_frame_structure == "PO" and _dim == 3)
     {
         state_size_ = 7;
         state_cov_size_ = 6;
-        dim_ = 3;
-    } else if (_frame_structure == "POV" and _dim == 3)
+    }else if (_frame_structure == "POV" and _dim == 3)
     {
         state_size_ = 10;
         state_cov_size_ = 9;
-        dim_ = 3;
+    }else if (_frame_structure == "POVCDL" and _dim == 3)
+    {
+        state_size_ = 19;
+        state_cov_size_ = 18;
     }
     else std::runtime_error(
             "Problem::Problem(): Unknown frame structure. Add appropriate frame structure to the switch statement.");
@@ -229,7 +231,7 @@ ProcessorBasePtr Problem::installProcessor(const std::string& _prc_type, //
 
     // adding processor is motion to the processor is motion vector
     if (prc_ptr->isMotion())
-        processor_is_motion_vec_.push_back(std::dynamic_pointer_cast<IsMotion>(prc_ptr));
+        processor_is_motion_list_.push_back(std::dynamic_pointer_cast<IsMotion>(prc_ptr));
 
     return prc_ptr;
 }
@@ -271,7 +273,7 @@ ProcessorBasePtr Problem::installProcessor(const std::string& _prc_type, //
 
     // adding processor is motion to the processor is motion vector
     if (prc_ptr->isMotion())
-        processor_is_motion_vec_.push_back(std::dynamic_pointer_cast<IsMotion>(prc_ptr));
+        processor_is_motion_list_.push_back(std::dynamic_pointer_cast<IsMotion>(prc_ptr));
 
     return prc_ptr;
 }
@@ -291,49 +293,6 @@ SensorBasePtr Problem::getSensor(const std::string& _sensor_name) const
     return (*sen_it);
 }
 
-void Problem::addProcessorMotion(IsMotionPtr _processor_motion_ptr)
-{
-    processor_is_motion_vec_.push_back(_processor_motion_ptr);
-}
-
-IsMotionPtr Problem::addProcessorMotion(const std::string& _processor_name)
-{
-    for (auto sen : getHardware()->getSensorList()) // loop all sensors
-    {
-        auto prc_it = std::find_if(sen->getProcessorList().begin(), // find processor by its name
-                                   sen->getProcessorList().end(),
-                                   [&](ProcessorBasePtr prc)
-                                   {
-                                       return prc->getName() == _processor_name;
-                                   }); // lambda function for the find_if
-
-        if (prc_it != sen->getProcessorList().end())  // found something!
-        {
-            if ((*prc_it)->isMotion()) // found, and it's motion!
-            {
-                std::cout << "Found processor '" << _processor_name << "', of type Motion, and added to the motion processor vector." << std::endl;
-                IsMotionPtr motion_processor_ptr = std::dynamic_pointer_cast<IsMotion>(*prc_it);
-                processor_is_motion_vec_.push_back(motion_processor_ptr);
-                return motion_processor_ptr;
-            }
-            else // found, but it's not motion!
-            {
-                std::cout << "Found processor '" << _processor_name << "', but not of type Motion!" << std::endl;
-                return nullptr;
-            }
-        }
-    }
-    // nothing found!
-    std::cout << "Processor '" << _processor_name << "' not found!" << std::endl;
-    return nullptr;
-}
-
-// Not used in the code based --> TODO
-// void Problem::clearProcessorMotion()
-// {
-//     processor_motion_ptr_.reset();
-// }
-
 FrameBasePtr Problem::emplaceFrame(const std::string& _frame_structure, //
                                    const SizeEigen _dim, //
                                    FrameType _frame_key_type, //
@@ -374,53 +333,88 @@ Eigen::VectorXd Problem::getCurrentState() const
 
 void Problem::getCurrentState(Eigen::VectorXd& _state) const
 {
-    if (processor_motion_ptr_ != nullptr)
-        processor_motion_ptr_->getCurrentState(_state);
-    else if (trajectory_ptr_->getLastKeyOrAuxFrame() != nullptr)
-        trajectory_ptr_->getLastKeyOrAuxFrame()->getState(_state);
-    else
-        _state = zeroState();
+    TimeStamp ts;  // throwaway timestamp
+    getCurrentStateAndStamp(_state, ts);
 }
 
-void Problem::getCurrentStateAndStamp(Eigen::VectorXd& _state, TimeStamp& ts) const
-{
-    if (processor_motion_ptr_ != nullptr)
+void Problem::getCurrentStateAndStamp(Eigen::VectorXd& _state, TimeStamp& _ts) const
+{   
+    if (!processor_is_motion_list_.empty())
     {
-        processor_motion_ptr_->getCurrentState(_state);
-        processor_motion_ptr_->getCurrentTimeStamp(ts);
+        // retrieve the minimum of the most recent ts in all processor is motion then call getSate(ts, state)
+        std::list<TimeStamp> proc_is_motion_current_ts;
+        for (auto proc: processor_is_motion_list_){
+            proc_is_motion_current_ts.push_back(proc->getCurrentTimeStamp());
+        }
+        auto min_it = std::min_element(proc_is_motion_current_ts.begin(), proc_is_motion_current_ts.end());
+        getState(*min_it, _state);
+        _ts = *min_it;
     }
     else if (trajectory_ptr_->getLastKeyOrAuxFrame() != nullptr)
     {
-        trajectory_ptr_->getLastKeyOrAuxFrame()->getTimeStamp(ts);
+        // kind of redundant with getState(_ts, _state)
+        trajectory_ptr_->getLastKeyOrAuxFrame()->getTimeStamp(_ts);
         trajectory_ptr_->getLastKeyOrAuxFrame()->getState(_state);
     }
     else
         _state = zeroState();
 }
-VectorXd full_state = problem->getCurrentState();
-Vector3d angular_momentum = full_state.segment<3>(16);
+
 
 void Problem::getState(const TimeStamp& _ts, Eigen::VectorXd& _state) const
 {
-    // try to get the state from processor_motion if any, otherwise...
-    // if (processor_motion_ptr_ == nullptr || !processor_motion_ptr_->getState(_ts, _state))
-    // {
-    //     FrameBasePtr closest_frame = trajectory_ptr_->closestKeyOrAuxFrameToTimeStamp(_ts);
-    //     if (closest_frame != nullptr)
-    //         closest_frame->getState(_state);
-    //     else
-    //         _state = zeroState();
-    // }
-    if (processor_is_motion_vec_.empty()){
+    // if _ts is too recent, for some of the processor is motion, they return the state corresponding to their last frame timestamp
+    if (processor_is_motion_list_.empty()){
         FrameBasePtr closest_frame = trajectory_ptr_->closestKeyOrAuxFrameToTimeStamp(_ts);
         if (closest_frame != nullptr)
             closest_frame->getState(_state);
         else
-            _state = zeroState();  // TODO: generic implementation ? 
+            _state = zeroState();
     }
     else {
-        std::list<Eigen::VectorXd> states_to_concat;
+        // Iterate over the problem state structure and get the corresponding state
+        // in the first processor is motion that provides it
+        // finally check if the state to concatenate list has the same total size as the problem state_size 
+        
+        // an map is necessary as a temporary structure because we do not know in which order we will find the state blocks in processors 
+        std::unordered_map<char, Eigen::VectorXd> states_to_concat_map;  // not necessary to be ordered
+        for (auto proc: processor_is_motion_list_){
+            Eigen::VectorXd proc_state = proc->getState(_ts);
+
+            int idx = 0;
+            for (char sb_name: proc->getStateStructure()){
+                if (states_to_concat_map.find(sb_name) != states_to_concat_map.end()){
+                    // not already there
+                    if (sb_name == 'O'){
+                        states_to_concat_map[sb_name] = proc_state.segment<4>(idx);
+                        idx += 4;
+                    }
+                    else{
+                        states_to_concat_map[sb_name] = proc_state.segment<3>(idx);
+                        idx += 3;
+                    } 
+                }
+            }
+        }
 
+        int concat_size = 0;
+        for (auto state_map_it: states_to_concat_map){
+            concat_size += state_map_it.second.size();
+        }
+        assert(concat_size == state_size_  && "Problem with the concatenated size");
+
+        // fill the state value from the state concatenation in the order dictated by frame_structure_
+        int idx = 0;
+        for (char sb_name: frame_structure_){
+            if (sb_name == 'O'){
+                _state.segment<4>(idx) = states_to_concat_map[sb_name];
+                idx += 4;
+            }
+            else {
+                _state.segment<3>(idx) = states_to_concat_map[sb_name];
+                idx += 3;
+            }
+        }
     }
 }
 
diff --git a/src/processor/processor_base.cpp b/src/processor/processor_base.cpp
index 302923f94..637aaa8ac 100644
--- a/src/processor/processor_base.cpp
+++ b/src/processor/processor_base.cpp
@@ -60,28 +60,28 @@ void ProcessorBase::captureCallback(CaptureBasePtr _capture_ptr)
         buffer_capture_.add(_capture_ptr->getTimeStamp(), _capture_ptr);
 }
 
-// Not used in the code base --> TODO
-// void ProcessorBase::remove()
-// {
-//     if (!is_removing_)
-//     {
-//         is_removing_ = true;
-//         ProcessorBasePtr this_p = shared_from_this();
-
-//         // clear Problem::processor_motion_ptr_
-//         if (isMotion())
-//         {
-//             ProblemPtr P = getProblem();
-//             if(P && (P->getProcessorMotion() == std::dynamic_pointer_cast<IsMotion>( shared_from_this() ) ) )
-//                 P->clearProcessorMotion();
-//         }
-
-//         // remove from upstream
-//         SensorBasePtr sen = sensor_ptr_.lock();
-//         if(sen)
-//             sen->removeProcessor(this_p);
-//     }
-// }
+// clearProcessorIsMotion liking error --> TODO
+void ProcessorBase::remove()
+{
+    // if (!is_removing_)
+    // {
+    //     is_removing_ = true;
+    //     ProcessorBasePtr this_p = shared_from_this();
+
+    //     if (isMotion())
+    //     {
+    //         ProblemPtr P = getProblem();
+    //         auto this_proc_cast_attempt = std::dynamic_pointer_cast<IsMotion>( shared_from_this() );
+    //         if(P && this_proc_cast_attempt )
+    //             P->clearProcessorIsMotion(this_proc_cast_attempt);
+    //     }
+
+    //     // remove from upstream
+    //     SensorBasePtr sen = sensor_ptr_.lock();
+    //     if(sen)
+    //         sen->removeProcessor(this_p);
+    // }
+}
 
 void ProcessorBase::link(SensorBasePtr _sen_ptr)
 {
diff --git a/src/processor/processor_motion.cpp b/src/processor/processor_motion.cpp
index 56e9adcad..a153c1ec7 100644
--- a/src/processor/processor_motion.cpp
+++ b/src/processor/processor_motion.cpp
@@ -17,7 +17,6 @@ ProcessorMotion::ProcessorMotion(const std::string& _type,
         ProcessorBase(_type, _params_motion),
         params_motion_(_params_motion),
         processing_step_(RUNNING_WITHOUT_PACK),
-        state_structure_(_state_structure),
         x_size_(_state_size),
         data_size_(_data_size),
         delta_size_(_delta_size),
@@ -35,7 +34,8 @@ ProcessorMotion::ProcessorMotion(const std::string& _type,
         jacobian_delta_preint_(delta_cov_size_, delta_cov_size_),
         jacobian_delta_(delta_cov_size_, delta_cov_size_),
         jacobian_calib_(delta_cov_size_, calib_size_)
-{
+{   
+    setStateStructure(_state_structure);
     //
 }
 
@@ -268,7 +268,7 @@ void ProcessorMotion::processCapture(CaptureBasePtr _incoming_ptr)
     // Update state and time stamps
     last_ptr_->setTimeStamp(getCurrentTimeStamp());
     last_ptr_->getFrame()->setTimeStamp(getCurrentTimeStamp());
-    last_ptr_->getFrame()->setState(getCurrentState());
+    last_ptr_->getFrame()->setState(getProblem()->getState(getCurrentTimeStamp()));
 
     if (permittedKeyFrame() && voteForKeyFrame())
     {
@@ -316,7 +316,7 @@ void ProcessorMotion::processCapture(CaptureBasePtr _incoming_ptr)
 
         // create a new frame
         auto frame_new      = getProblem()->emplaceFrame(NON_ESTIMATED,
-                                                        getCurrentState(),
+                                                        getProblem()->getCurrentState(),
                                                         getCurrentTimeStamp());
         // create a new capture
         auto capture_new    = emplaceCapture(frame_new,
@@ -361,7 +361,7 @@ bool ProcessorMotion::getState(const TimeStamp& _ts, Eigen::VectorXd& _x) const
     {
         // Get origin state and calibration
         CaptureBasePtr cap_orig   = capture_motion->getOriginCapture();
-        VectorXd state_0          = cap_orig->getFrame()->getState();
+        VectorXd state_0          = cap_orig->getFrame()->getState(state_structure_);
         VectorXd calib            = cap_orig->getCalibration();
 
         // Get delta and correct it with new calibration params
@@ -413,9 +413,10 @@ void ProcessorMotion::setOrigin(FrameBasePtr _origin_frame)
 
     // ---------- LAST ----------
     // Make non-key-frame for last Capture
+    TimeStamp origin_ts = _origin_frame->getTimeStamp();
     auto new_frame_ptr  = getProblem()->emplaceFrame(NON_ESTIMATED,
-                                                     _origin_frame->getState(),
-                                                     _origin_frame->getTimeStamp());
+                                                     getProblem()->getState(origin_ts),
+                                                     origin_ts);
     // emplace (emtpy) last Capture
     last_ptr_ = emplaceCapture(new_frame_ptr,
                                getSensor(),
@@ -627,11 +628,6 @@ void ProcessorMotion::setProblem(ProblemPtr _problem)
     // set the origin
     if (origin_ptr_ == nullptr && this->getProblem()->getLastKeyFrame() != nullptr)
         this->setOrigin(this->getProblem()->getLastKeyFrame());
-
-    // set the main processor motion
-    if (this->getProblem()->getProcessorMotion() == nullptr){
-        this->getProblem()->addProcessorMotion(std::static_pointer_cast<ProcessorMotion>(shared_from_this()));
-    }
 };
 
 bool ProcessorMotion::storeKeyFrame(FrameBasePtr _frame_ptr)
diff --git a/test/gtest_problem.cpp b/test/gtest_problem.cpp
index 17f39d09f..a7cae940e 100644
--- a/test/gtest_problem.cpp
+++ b/test/gtest_problem.cpp
@@ -89,7 +89,7 @@ TEST(Problem, Processor)
     ProblemPtr P = Problem::create("PO", 3);
 
     // check motion processor is null
-    ASSERT_FALSE(P->getProcessorMotion());
+    ASSERT_FALSE(P->getProcessorIsMotion());
 
     // add a motion sensor and processor
     auto Sm = SensorBase::emplace<SensorOdom3D>(P->getHardware(), (Eigen::Vector7d()<<0,0,0, 0,0,0,1).finished(), ParamsSensorOdom3D());
@@ -98,7 +98,7 @@ TEST(Problem, Processor)
     auto Pm = ProcessorBase::emplace<ProcessorOdom3D>(Sm, std::make_shared<ProcessorParamsOdom3D>());
 
     // check motion processor IS NOT by emplace
-    ASSERT_EQ(P->getProcessorMotion(), Pm);
+    ASSERT_EQ(P->getProcessorIsMotion(), Pm);
 }
 
 TEST(Problem, Installers)
@@ -113,16 +113,16 @@ TEST(Problem, Installers)
     auto pt = P->installProcessor("ProcessorTrackerFeatureDummy", "dummy", "odometer");
 
     // check motion processor IS NOT set
-    ASSERT_FALSE(P->getProcessorMotion());
+    ASSERT_FALSE(P->getProcessorIsMotion());
 
     // install processor motion
     ProcessorBasePtr pm = P->installProcessor("ProcessorOdom3D", "odom integrator", "odometer", wolf_root + "/test/yaml/processor_odom_3D.yaml");
 
     // check motion processor is set
-    ASSERT_TRUE(P->getProcessorMotion());
+    ASSERT_TRUE(P->getProcessorIsMotion() != nullptr);
 
     // check motion processor is correct
-    ASSERT_EQ(std::dynamic_pointer_cast<ProcessorMotion>(P->getProcessorMotion()), pm);
+    ASSERT_EQ(std::dynamic_pointer_cast<ProcessorMotion>(P->getProcessorIsMotion()), pm);
 }
 
 TEST(Problem, SetOrigin_PO_2D)
-- 
GitLab