diff --git a/include/core/landmark/landmark_base.h b/include/core/landmark/landmark_base.h
index db28f5720e127904862cbb4f6ad35c6a34ed5347..bb45a8bcf3562fa41caf3f70180de0d9bc5c0a2b 100644
--- a/include/core/landmark/landmark_base.h
+++ b/include/core/landmark/landmark_base.h
@@ -20,12 +20,6 @@
 
 #pragma once
 
-// // Fwd references
-// namespace wolf{
-// class MapBase;
-// class StateBlock;
-// }
-
 // Wolf includes
 #include "core/common/wolf.h"
 #include "core/common/node_state_blocks.h"
@@ -97,6 +91,7 @@ class LandmarkBase : public NodeStateBlocks
     // Navigate wolf tree
     void         setProblem(ProblemPtr _problem) override final;
     unsigned int landmark_id_;  ///< landmark unique id
+    unsigned int track_id_;     ///< associated track id
     TimeStamp    stamp_;        ///< stamp of the creation of the landmark
 
   public:
@@ -124,6 +119,9 @@ class LandmarkBase : public NodeStateBlocks
     unsigned int id() const override;
     void         setId(unsigned int _id);
 
+    unsigned int trackId();                           // get track ID
+    void         setTrackId(unsigned int _track_id);  // set track ID
+
   public:
     MapBaseConstPtr getMap() const;
     MapBasePtr      getMap();
@@ -162,7 +160,6 @@ class LandmarkBase : public NodeStateBlocks
         return std::static_pointer_cast<const LandmarkBase>(shared_from_this());
     };
 };
-
 }  // namespace wolf
 
 #include "core/map/map_base.h"
@@ -205,4 +202,14 @@ inline void LandmarkBase::setId(unsigned int _id)
     if (_id > landmark_id_count_) landmark_id_count_ = _id;
 }
 
+inline unsigned int LandmarkBase::trackId()
+{
+    return track_id_;
+}
+
+inline void LandmarkBase::setTrackId(unsigned int _track_id)
+{
+    track_id_ = _track_id;
+}
+
 }  // namespace wolf
diff --git a/include/core/processor/processor_tracker.h b/include/core/processor/processor_tracker.h
index 9b088c8a4242dfc1ba30814bbf4b21e39e3a9211..b1ba8acb7f3c77791ef3c0ea1015ed50dadbf472 100644
--- a/include/core/processor/processor_tracker.h
+++ b/include/core/processor/processor_tracker.h
@@ -97,7 +97,7 @@ class ProcessorTracker : public ProcessorBase
     FeatureBasePtrList
         new_features_incoming_;  ///< list of the new features of \b last successfully tracked in \b incoming
     FeatureBasePtrList
-        known_features_last_;  ///< list of the known features in previous captures successfully tracked in \b last
+        known_features_last_;    ///< list of the known features in previous captures successfully tracked in \b last
     FeatureBasePtrList
               known_features_incoming_;  ///< list of the known features in \b last successfully tracked in \b incoming
     StateKeys state_keys_;               ///< Keys of frames created or used by this processor
@@ -117,6 +117,8 @@ class ProcessorTracker : public ProcessorBase
     virtual CaptureBasePtr      getOrigin();
     virtual CaptureBaseConstPtr getLast() const;
     virtual CaptureBasePtr      getLast();
+    virtual FrameBaseConstPtr   getLastFrame() const;
+    virtual FrameBasePtr        getLastFrame();
     virtual CaptureBaseConstPtr getIncoming() const;
     virtual CaptureBasePtr      getIncoming();
 
@@ -323,6 +325,16 @@ inline CaptureBasePtr ProcessorTracker::getLast()
     return last_ptr_;
 }
 
+inline FrameBaseConstPtr ProcessorTracker::getLastFrame() const
+{
+    return last_frame_ptr_;
+}
+
+inline FrameBasePtr ProcessorTracker::getLastFrame()
+{
+    return last_frame_ptr_;
+}
+
 inline CaptureBaseConstPtr ProcessorTracker::getIncoming() const
 {
     return incoming_ptr_;
diff --git a/src/landmark/landmark_base.cpp b/src/landmark/landmark_base.cpp
index 6ab302315fa9e9b5da2b8de1326ba940e934ae14..d592fb41b0d5098392b50f93a4e664c70874c26d 100644
--- a/src/landmark/landmark_base.cpp
+++ b/src/landmark/landmark_base.cpp
@@ -32,19 +32,6 @@ namespace wolf
 {
 unsigned int LandmarkBase::landmark_id_count_ = 0;
 
-// LandmarkBase::LandmarkBase(const std::string& _type, StateBlockPtr _p_ptr, StateBlockPtr _o_ptr)
-//     : NodeStateBlocks("LANDMARK", _type), map_ptr_(), landmark_id_(++landmark_id_count_)
-// {
-//     if (_p_ptr)
-//     {
-//         addStateBlock('P', _p_ptr);
-//     }
-//     if (_o_ptr)
-//     {
-//         addStateBlock('O', _o_ptr);
-//     }
-// }
-
 LandmarkBase::LandmarkBase(const std::string& _type, const SpecStateComposite& _state_specs)
     : NodeStateBlocks("LANDMARK", _type, _state_specs), map_ptr_(), landmark_id_(++landmark_id_count_)
 {
@@ -57,13 +44,6 @@ LandmarkBase::LandmarkBase(const std::string& _type, const YAML::Node& _n)
 {
 }
 
-// LandmarkBase::LandmarkBase(const YAML::Node& _n)
-//     : NodeStateBlocks("LANDMARK", "LandmarkBase", SpecStateComposite(_n["states"])),
-//       map_ptr_(),
-//       landmark_id_(_n["id"].as<int>())
-// {
-// }
-
 void LandmarkBase::remove(bool viral_remove_parent_without_children)
 {
     /* Order of removing:
@@ -186,7 +166,4 @@ bool LandmarkBase::check(CheckLog& _log, bool _verbose, std::ostream& _stream, s
     return _log.is_consistent_;
 }
 
-// Register landmark creator
-// WOLF_REGISTER_LANDMARK(LandmarkBase);
-
 }  // namespace wolf
diff --git a/src/processor/processor_tracker.cpp b/src/processor/processor_tracker.cpp
index bc093a4e338c9b73f2eb2313ce78c286c1d92356..eb8b347297034377673c0345ab170d18a075f6d6 100644
--- a/src/processor/processor_tracker.cpp
+++ b/src/processor/processor_tracker.cpp
@@ -78,10 +78,24 @@ void ProcessorTracker::processCapture(CaptureBasePtr _incoming_ptr)
                        " callback unpacked with ts= ",
                        keyframe_from_callback->getTimeStamp());
 
-            // Append incoming to KF
-            incoming_ptr_->link(keyframe_from_callback);
+            // check if the callback keyframe has a capture of this sensor
+            auto capture_from_callback = keyframe_from_callback->getCaptureOf(this->getSensor());
+
+            if (incoming_ptr_ == capture_from_callback)
+            {
+                // If captures match, then frames must match too
+                assert(incoming_ptr_->getFrame() != nullptr and incoming_ptr_->getFrame() == keyframe_from_callback and
+                       "The keyframe has a Capture from this sensor, but this capture is not incoming!");
+                WOLF_DEBUG("PT ", getName(), " Incoming capture has been processed previously by another processor!")
+            }
+            else
+            {
+                WOLF_DEBUG("PT ", getName(), " Incoming capture had not been processed by any other processor!")
+
+                // Join KF
+                incoming_ptr_->link(keyframe_from_callback);
+            }
 
-            // Process info
             // TrackerFeature:  We only process new features in Last, here last = nullptr, so we do not have anything
             // to do. TrackerLandmark: If we have been given a map, all landmarks in the map are known. Process them.
             processKnown();
@@ -89,25 +103,34 @@ void ProcessorTracker::processCapture(CaptureBasePtr _incoming_ptr)
             // Reset this
             resetDerived();
             // Update pointers
-            origin_ptr_   = incoming_ptr_;
-            last_ptr_     = incoming_ptr_;
-            incoming_ptr_ = nullptr;
+            origin_ptr_     = incoming_ptr_;
+            last_ptr_       = incoming_ptr_;
+            last_frame_ptr_ = keyframe_from_callback;
+            incoming_ptr_   = nullptr;
 
             break;
         }
         case FIRST_TIME_WITHOUT_KEYFRAME: {
             WOLF_DEBUG("PT ", getName(), " FIRST_TIME_WITHOUT_KEYFRAME");
 
+            // Check if incoming has already a Frame
+            auto frame_incoming = incoming_ptr_->getFrame();
+            assert(frame_incoming == nullptr and
+                   " Incoming capture has been processed and linked by another processor, but no keyframe callback "
+                   "was received!");
+
+            WOLF_DEBUG("PT ", getName(), " Incoming capture has not been processed by another processor!")
+
             // make a new KF at incoming
             FrameBasePtr keyframe = getProblem()->emplaceFrame(incoming_ptr_->getTimeStamp());
 
-            // link incoming to the new KF
+            // Append incoming to KF
             incoming_ptr_->link(keyframe);
 
             // Process info
             // TrackerFeature:  We only process new features in Last, here last = nullptr, so we do not have anything
             // to do. TrackerLandmark: If we have been given a map, all landmarks in the map are known. Process them.
-            if (not getProblem()->getMap()->getLandmarkList().empty()) processKnown();
+            processKnown();
 
             // Issue KF callback with new KF
             getProblem()->keyFrameCallback(keyframe, shared_from_this());
@@ -115,9 +138,10 @@ void ProcessorTracker::processCapture(CaptureBasePtr _incoming_ptr)
             // Reset this
             resetDerived();
             // Update pointers
-            origin_ptr_   = incoming_ptr_;
-            last_ptr_     = incoming_ptr_;
-            incoming_ptr_ = nullptr;
+            origin_ptr_     = incoming_ptr_;
+            last_ptr_       = incoming_ptr_;
+            last_frame_ptr_ = keyframe;
+            incoming_ptr_   = nullptr;
 
             break;
         }
@@ -146,14 +170,12 @@ void ProcessorTracker::processCapture(CaptureBasePtr _incoming_ptr)
             WOLF_DEBUG("PT ", getName(), " SECOND_TIME_WITHOUT_KEYFRAME");
 
             // Make a NON KEY Frame to hold incoming capture
-            FrameBasePtr keyframe = std::make_shared<FrameBase>(
-                incoming_ptr_->getTimeStamp(), getProblem()->getFrameTypes(), getProblem()->getState());
-            incoming_ptr_->link(keyframe);
+            FrameBasePtr frame = std::make_shared<FrameBase>(incoming_ptr_->getTimeStamp(),
+                                                             getProblem()->getFrameTypes(),
+                                                             getProblem()->getState(incoming_ptr_->getTimeStamp()));
 
-            // Process info
-            // If we have known landmarks or features. Process them.
-            if (not getProblem()->getMap()->getLandmarkList().empty() or not known_features_last_.empty())
-                processKnown();
+            // Process known information
+            processKnown();
 
             // Both Trackers:  We have a last_ Capture with not enough features, so populate it.
             processNew(max_new_features_);
@@ -166,7 +188,7 @@ void ProcessorTracker::processCapture(CaptureBasePtr _incoming_ptr)
             // Update pointers
             origin_ptr_     = last_ptr_;
             last_ptr_       = incoming_ptr_;
-            last_frame_ptr_ = keyframe;
+            last_frame_ptr_ = frame;
             incoming_ptr_   = nullptr;
 
             break;
@@ -184,15 +206,28 @@ void ProcessorTracker::processCapture(CaptureBasePtr _incoming_ptr)
 
             processKnown();
 
-            // Capture last_ is added to the new keyframe
-            FrameBasePtr last_old_frame = last_ptr_->getFrame();
-            last_ptr_->move(keyframe_from_callback);
-            last_old_frame->remove();
+            // chack if the received KF has a capture of this sensor, and if it matches with last_ptr
+            if (last_ptr_ == keyframe_from_callback->getCaptureOf(this->getSensor()))
+            {
+                WOLF_DEBUG("PT ", getName(), " Last capture has been processed previously by another processor!")
+
+                // If captures match, then frames must match too
+                assert(last_ptr_->getFrame() == keyframe_from_callback and
+                       "The keyframe has a Capture from this sensor, but this capture is not last!");
+
+                // No need to join KF since it is the same capture, and it was already joined by the other processor
+            }
+            else
+            {
+                WOLF_DEBUG("PT ", getName(), " Last capture had not been processed previously!")
+
+                // join KF
+                last_ptr_->link(keyframe_from_callback);
+            }
 
             // Create new NON KEY frame for incoming
             FrameBasePtr frame = std::make_shared<FrameBase>(
                 incoming_ptr_->getTimeStamp(), getProblem()->getFrameTypes(), getProblem()->getState());
-            incoming_ptr_->link(frame);
 
             // Detect new Features, initialize Landmarks, ...
             processNew(max_new_features_);
@@ -222,21 +257,21 @@ 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()->link(getProblem());
+                last_frame_ptr_->setState(getProblem()->getState(last_ptr_->getTimeStamp()));
+                last_ptr_->link(last_frame_ptr_);
+                last_frame_ptr_->link(getProblem());
 
                 // Establish factors
                 establishFactors();
 
-                // Call the new keyframe callback in order to let the other processors to establish their factors
-                getProblem()->keyFrameCallback(last_ptr_->getFrame(), shared_from_this());
+                // Call the new keyframe callback in order to let the other processors to join
+                getProblem()->keyFrameCallback(last_frame_ptr_, shared_from_this());
 
                 // make NON KEY frame; append incoming to new frame
                 FrameBasePtr frame =
                     std::make_shared<FrameBase>(incoming_ptr_->getTimeStamp(),
                                                 getProblem()->getFrameTypes(),
                                                 getProblem()->getState(incoming_ptr_->getTimeStamp()));
-                incoming_ptr_->link(frame);
 
                 // Reset this
                 resetDerived();
@@ -255,9 +290,6 @@ void ProcessorTracker::processCapture(CaptureBasePtr _incoming_ptr)
                     std::make_shared<FrameBase>(incoming_ptr_->getTimeStamp(),
                                                 getProblem()->getFrameTypes(),
                                                 getProblem()->getState(incoming_ptr_->getTimeStamp()));
-                incoming_ptr_->link(frame);
-                last_ptr_->unlink();  // unlink last (destroying the frame) instead of frame destruction that would
-                                      // implicitly destroy last
 
                 // Advance this
                 advanceDerived();
@@ -315,7 +347,7 @@ void ProcessorTracker::computeProcessingStep()
 
             if (buffer_frame_.select(last_ptr_->getTimeStamp(), getTimeTolerance()))
             {
-                if (last_ptr_->getFrame()->getProblem())
+                if (last_frame_ptr_->getProblem())
                 {
                     WOLF_WARN("||*||");
                     WOLF_INFO(" ... It seems you missed something!");
@@ -348,7 +380,7 @@ void ProcessorTracker::printHeader(int           _depth,
     if (getLast())
         _stream << _tabs << "  "
                 << "l: Cap" << getLast()->id() << " - "
-                << " Frm" << getLast()->getFrame()->id() << std::endl;
+                << " Frm" << getLastFrame()->id() << std::endl;
     if (getIncoming())
         _stream << _tabs << "  "
                 << "i: Cap" << getIncoming()->id() << std::endl;
diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt
index 15eda28dde6e9a9f93ffcc82c69fe51bb440a274..ee49b777b3bf3923ce4dd79b6ffa29863ab23bec 100644
--- a/test/CMakeLists.txt
+++ b/test/CMakeLists.txt
@@ -237,6 +237,10 @@ wolf_add_gtest(gtest_processor_pose_3d gtest_processor_pose_3d.cpp)
 wolf_add_gtest(gtest_processor_tracker_feature_dummy gtest_processor_tracker_feature_dummy.cpp)
 target_link_libraries(gtest_processor_tracker_feature_dummy PUBLIC dummy)
 
+# ProcessorTrackerFeatureDummy 2 processors in one sensor test
+wolf_add_gtest(gtest_processor_tracker_two_processors_one_sensor gtest_processor_tracker_two_processors_one_sensor.cpp)
+target_link_libraries(gtest_processor_tracker_two_processors_one_sensor PUBLIC dummy)
+
 # ProcessorTrackerLandmarkDummy class test
 wolf_add_gtest(gtest_processor_tracker_landmark_dummy gtest_processor_tracker_landmark_dummy.cpp)
 target_link_libraries(gtest_processor_tracker_landmark_dummy PUBLIC dummy)
diff --git a/test/gtest_processor_landmark_external.cpp b/test/gtest_processor_landmark_external.cpp
index 86876ba99979090ab2ce95bdb1cd3886e0850622..639557872955a83c4257c070bc897b7900ae42eb 100644
--- a/test/gtest_processor_landmark_external.cpp
+++ b/test/gtest_processor_landmark_external.cpp
@@ -294,16 +294,16 @@ void ProcessorLandmarkExternalTest::testConfiguration(int    dim,
             ASSERT_FALSE(fac_list.empty());
 
             // factors' type
-            if (should_emplace_KF)
-                for (auto fac : fac_list)
+            for (auto fac : fac_list)
+            {
+                if (fac->getProcessor() == processor)
                 {
-                    if (fac->getProcessor() == processor)
-                    {
-                        ASSERT_EQ(fac->getType(),
-                                  std::string("FactorRelative") + (orientation ? "Pose" : "Position") +
-                                      (dim == 2 ? "2d" : "3d") + "WithExtrinsics");
-                    }
+                    ASSERT_EQ(fac->getType(),
+                              std::string("FactorRelative") + (orientation ? "Pose" : "Position") +
+                                  (dim == 2 ? "2d" : "3d") + "WithExtrinsics");
                 }
+            }
+
             // landmarks created by processor
             if (not add_landmarks)
             {
diff --git a/test/gtest_processor_tracker_feature_dummy.cpp b/test/gtest_processor_tracker_feature_dummy.cpp
index 28eee1c8abc5a6a274a4c50a4a0f8bc1f599a8b6..35b658aaf493303fe1471738cbd48b091d2a09b5 100644
--- a/test/gtest_processor_tracker_feature_dummy.cpp
+++ b/test/gtest_processor_tracker_feature_dummy.cpp
@@ -44,7 +44,7 @@ class ProcessorTrackerFeatureDummyTest : public testing::Test
         // Wolf problem
         problem = Problem::create("PO", 2);
 
-        // Install camera
+        // Install sensor
         sensor = problem->installSensor(wolf_dir + "/test/yaml/sensor_odom_2d.yaml", {wolf_dir});
 
         // Install processor
@@ -119,7 +119,7 @@ TEST_F(ProcessorTrackerFeatureDummyTest, processNew)
     CaptureBasePtr inc_cap = std::make_shared<CaptureVoid>(1, sensor);
     processor->setInc(inc_cap);
 
-    auto n_new_feat = processor->callProcessNew(10);  // detect 10 features
+    auto n_new_feat = processor->callProcessNew(10);                  // detect 10 features
 
     ASSERT_EQ(n_new_feat, 10);                                        // detected 10 features
     ASSERT_EQ(processor->getLast()->getFeatureList().size(), 10);     // detected 10 features
@@ -140,13 +140,13 @@ TEST_F(ProcessorTrackerFeatureDummyTest, processKnown)
     CaptureBasePtr inc_cap = std::make_shared<CaptureVoid>(1, sensor);
     processor->setInc(inc_cap);
 
-    processor->callProcessNew(15);  // detect 15 features, 1 track lost per tracking
+    processor->callProcessNew(15);                                     // detect 15 features, 1 track lost per tracking
 
     ASSERT_EQ(processor->getLast()->getFeatureList().size(), 15);      // detected 15 features
     ASSERT_EQ(processor->getIncoming()->getFeatureList().size(), 14);  // 1 track lost
     ASSERT_EQ(processor->getMatchesLastFromIncoming().size(), 14);     // 1 track lost
 
-    processor->callReset();  // now incoming is last and last is origin
+    processor->callReset();                                            // now incoming is last and last is origin
 
     // Put a capture on last_ptr_
     CaptureBasePtr new_cap = std::make_shared<CaptureVoid>(0, sensor);
@@ -203,13 +203,13 @@ TEST_F(ProcessorTrackerFeatureDummyTest, establishFactors)
     CaptureBasePtr inc_cap = CaptureBase::emplace<CaptureVoid>(inc_frm, 1, sensor);
     processor->setInc(inc_cap);
 
-    processor->callProcessNew(15);  // detect 15 features, 1 track lost per tracking
+    processor->callProcessNew(15);                                     // detect 15 features, 1 track lost per tracking
 
     ASSERT_EQ(processor->getLast()->getFeatureList().size(), 15);      // detected 15 features
     ASSERT_EQ(processor->getIncoming()->getFeatureList().size(), 14);  // 1 track lost
     ASSERT_EQ(processor->getMatchesLastFromIncoming().size(), 14);     // 1 track lost
 
-    processor->callReset();  // now incoming is last and last is origin
+    processor->callReset();                                            // now incoming is last and last is origin
 
     // test establishFactors()
     processor->callEstablishFactors();
diff --git a/test/gtest_processor_tracker_two_processors_one_sensor.cpp b/test/gtest_processor_tracker_two_processors_one_sensor.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..117a7c9341aa6d9dfc967509c496971d89c60103
--- /dev/null
+++ b/test/gtest_processor_tracker_two_processors_one_sensor.cpp
@@ -0,0 +1,149 @@
+// WOLF - Copyright (C) 2020,2021,2022,2023
+// Institut de Robòtica i Informàtica Industrial, CSIC-UPC.
+// Authors: Joan Solà Ortega (jsola@iri.upc.edu) and
+// Joan Vallvé Navarro (jvallve@iri.upc.edu)
+// All rights reserved.
+//
+// This file is part of WOLF: http://www.iri.upc.edu/wolf
+// WOLF is free software: you can redistribute it and/or modify
+// it under the terms of the GNU Lesser General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// at your option) any later version.
+//
+// This program is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+// GNU Lesser General Public License for more details.
+//
+// You should have received a copy of the GNU Lesser General Public License
+// along with this program.  If not, see <http://www.gnu.org/licenses/>.
+
+// wolf includes
+#include "core/utils/utils_gtest.h"
+#include "core/sensor/factory_sensor.h"
+#include "dummy/processor_tracker_feature_dummy.h"
+#include "core/capture/capture_void.h"
+
+using namespace wolf;
+
+std::string wolf_dir = _WOLF_CODE_DIR;
+
+// Use the following in case you want to initialize tests with predefines variables or methods.
+class ProcessorTrackerFeatureDummyDoubledTest : public testing::Test
+{
+  public:
+    ProblemPtr                      problem;
+    SensorBasePtr                   sensor;
+    ProcessorTrackerFeatureDummyPtr processor_1, processor_2;
+
+    void SetUp() override
+    {
+        // Wolf problem
+        problem = Problem::create("PO", 2);
+
+        // Install sensor
+        sensor = problem->installSensor(wolf_dir + "/test/yaml/sensor_odom_2d.yaml", {wolf_dir});
+
+        // Install processors
+        processor_1 = std::static_pointer_cast<ProcessorTrackerFeatureDummy>(problem->installProcessor(
+            sensor, wolf_dir + "/test/yaml/processor_tracker_two_processors_1.yaml", {wolf_dir}));
+        processor_2 = std::static_pointer_cast<ProcessorTrackerFeatureDummy>(problem->installProcessor(
+            sensor, wolf_dir + "/test/yaml/processor_tracker_two_processors_2.yaml", {wolf_dir}));
+
+        problem->print(4, 1, 1, 1);
+    }
+};
+
+TEST_F(ProcessorTrackerFeatureDummyDoubledTest, installProcessor)
+{
+    ASSERT_EQ(processor_1->getProblem(), problem);
+    ASSERT_EQ(processor_2->getProblem(), problem);
+    ASSERT_TRUE(problem->check(0));
+}
+
+TEST_F(ProcessorTrackerFeatureDummyDoubledTest, process_one_prc)
+{
+    // Create a capture
+    CaptureBasePtr capture = std::make_shared<CaptureVoid>(0, sensor);
+
+    // Process by one processor
+    processor_1->captureCallback(capture);
+
+    problem->print(4, 1, 1, 1);
+}
+
+TEST_F(ProcessorTrackerFeatureDummyDoubledTest, process_once_one_prc_then_other)
+{
+    // Create a capture
+    CaptureBasePtr capture = std::make_shared<CaptureVoid>(0, sensor);
+
+    // Process by one processor
+    processor_1->captureCallback(capture);
+    auto frame_1 = capture->getFrame();
+
+    // Process by the other processor
+    processor_2->captureCallback(capture);
+    auto frame_2 = capture->getFrame();
+
+    problem->print(4, 1, 1, 1);
+
+    ASSERT_EQ(problem->getTrajectory()->getFrameMap().size(), 1);
+
+    ASSERT_EQ(frame_1, frame_2);
+}
+
+TEST_F(ProcessorTrackerFeatureDummyDoubledTest, process_once)
+{
+    // Process by both processors automatically in sequence
+    CaptureBasePtr capture = std::make_shared<CaptureVoid>(0, sensor);
+    capture->process();
+    problem->print(4, 1, 1, 1);
+
+    ASSERT_EQ(problem->getTrajectory()->getFrameMap().size(), 1);
+}
+
+TEST_F(ProcessorTrackerFeatureDummyDoubledTest, process_twice)
+{
+    // Process by both processors automatically in sequence
+
+    CaptureBasePtr capture = std::make_shared<CaptureVoid>(0, sensor);
+    capture->process();
+
+    capture = std::make_shared<CaptureVoid>(1, sensor);
+    capture->process();
+
+    problem->print(4, 1, 1, 1);
+}
+
+TEST_F(ProcessorTrackerFeatureDummyDoubledTest, process_thrice)
+{
+    // Create a capture
+    CaptureBasePtr capture = std::make_shared<CaptureVoid>(0, sensor);
+
+    // Process by both processors automatically in sequence
+    capture->process();
+
+    capture = std::make_shared<CaptureVoid>(1, sensor);
+    capture->process();
+
+    capture = std::make_shared<CaptureVoid>(2, sensor);
+    capture->process();
+
+    problem->print(2, 1, 1, 1);
+}
+
+TEST_F(ProcessorTrackerFeatureDummyDoubledTest, process_loop)
+{
+    for (TimeStamp t(0); t <= 6; t = t + 1)
+    {
+        auto capture = std::make_shared<CaptureVoid>(t, sensor);
+        capture->process();
+    }
+    problem->print(2, 1, 1, 1);
+}
+
+int main(int argc, char** argv)
+{
+    testing::InitGoogleTest(&argc, argv);
+    return RUN_ALL_TESTS();
+}
diff --git a/test/yaml/processor_tracker_two_processors_1.yaml b/test/yaml/processor_tracker_two_processors_1.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..1b71975c9e4cec7379cc66d0c535cbc7e4a3928b
--- /dev/null
+++ b/test/yaml/processor_tracker_two_processors_1.yaml
@@ -0,0 +1,10 @@
+name: processor_1
+type: ProcessorTrackerFeatureDummy
+plugin: core
+time_tolerance: 0.5
+keyframe_vote:
+  voting_active: true
+  min_features_for_keyframe: 7
+apply_loss_function: false
+max_new_features: 10
+n_tracks_lost: 2
\ No newline at end of file
diff --git a/test/yaml/processor_tracker_two_processors_2.yaml b/test/yaml/processor_tracker_two_processors_2.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..ef69a2eb0323488d73d68201ad4b007bcf5c5dd9
--- /dev/null
+++ b/test/yaml/processor_tracker_two_processors_2.yaml
@@ -0,0 +1,10 @@
+name: processor_2
+type: ProcessorTrackerFeatureDummy
+plugin: core
+time_tolerance: 0.5
+keyframe_vote:
+  voting_active: true
+  min_features_for_keyframe: 7
+apply_loss_function: false
+max_new_features: 10
+n_tracks_lost: 2
\ No newline at end of file