diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index fa636c272c531d07c79a646e2b589e4e3c546636..68429f566e0a6ac6f7d5f48385f2170df42bbdef 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -100,8 +100,6 @@ license_header: build_and_test:bionic: stage: build_and_test image: labrobotica/wolf_deps:18.04 - except: - - master script: #- *cmake316_definition - *build_and_test_definition @@ -110,8 +108,6 @@ build_and_test:bionic: build_and_test:focal: stage: build_and_test image: labrobotica/wolf_deps:20.04 - except: - - master script: - *build_and_test_definition diff --git a/demos/hello_wolf/hello_wolf_autoconf.cpp b/demos/hello_wolf/hello_wolf_autoconf.cpp index db934ca13174443de5053e3a427206de41799c18..27214245096f91fefad1351f611613516010f40a 100644 --- a/demos/hello_wolf/hello_wolf_autoconf.cpp +++ b/demos/hello_wolf/hello_wolf_autoconf.cpp @@ -138,8 +138,8 @@ int main() SolverManagerPtr ceres = FactorySolver::create("SolverCeres", problem, server); // recover sensor pointers and other stuff for later use (access by sensor name) - SensorBasePtr sensor_odo = problem->getSensor("sen odom"); - SensorBasePtr sensor_rb = problem->getSensor("sen rb"); + SensorBasePtr sensor_odo = problem->findSensor("sen odom"); + SensorBasePtr sensor_rb = problem->findSensor("sen rb"); // APPLY PRIOR and SET PROCESSOR ODOM ORIGIN =================================================== TimeStamp t(0.0); diff --git a/include/core/problem/problem.h b/include/core/problem/problem.h index 7405ae8320deb339ed6efdfe7319b4df8ec14cff..08a7ab52fd0598315adf2b9150ad80efd77043d0 100644 --- a/include/core/problem/problem.h +++ b/include/core/problem/problem.h @@ -151,7 +151,11 @@ class Problem : public std::enable_shared_from_this<Problem> /** \brief get a sensor pointer by its name * \param _sensor_name The sensor name, as it was installed with installSensor() */ - SensorBasePtr getSensor(const std::string& _sensor_name) const; + SensorBasePtr findSensor(const std::string& _sensor_name) const; + /** \brief get a processor pointer by its name + * \param _processor_name The processor name, as it was installed with installProcessor() + */ + ProcessorBasePtr findProcessor(const std::string& _processor_name) const; /** \brief Factory method to install (create, and add to sensor) processors only from its properties * diff --git a/include/core/processor/track_matrix.h b/include/core/processor/track_matrix.h index fa18d8313c591905b2b093e15261c18a5a69e8f2..e60a59f8233abb7fade714f20cbabc417a76e091 100644 --- a/include/core/processor/track_matrix.h +++ b/include/core/processor/track_matrix.h @@ -119,6 +119,8 @@ class TrackMatrix FeatureBasePtr feature (const SizeStd& _track_id, CaptureBasePtr _cap) const; CaptureBasePtr firstCapture(const SizeStd& _track_id) const; + list<size_t> trackIds() const; + // tracks across captures that belong to keyframe Track trackAtKeyframes(size_t _track_id) const; diff --git a/src/problem/problem.cpp b/src/problem/problem.cpp index d2078f8ac2cc8dad9cef2a835dd2c174f664d6e0..bdc8b8c70e15e01b969f515250ee11ec218bed04 100644 --- a/src/problem/problem.cpp +++ b/src/problem/problem.cpp @@ -300,7 +300,7 @@ ProcessorBasePtr Problem::installProcessor(const std::string& _prc_type, // const std::string& _corresponding_sensor_name, // const std::string& _params_filename) { - SensorBasePtr sen_ptr = getSensor(_corresponding_sensor_name); + SensorBasePtr sen_ptr = findSensor(_corresponding_sensor_name); if (sen_ptr == nullptr) throw std::runtime_error("Cannot bind processor. Reason: Sensor \"" + _corresponding_sensor_name + "\" not found. Check sensor name, it must match in sensor and processor!"); if (_params_filename == "") @@ -318,7 +318,7 @@ ProcessorBasePtr Problem::installProcessor(const std::string& _prc_type, // const std::string& _corresponding_sensor_name, // const ParamsServer& _server) { - SensorBasePtr sen_ptr = getSensor(_corresponding_sensor_name); + SensorBasePtr sen_ptr = findSensor(_corresponding_sensor_name); if (sen_ptr == nullptr) throw std::runtime_error("Cannot bind processor. Reason: Sensor \"" + _corresponding_sensor_name + "\" not found. Check sensor name, it must match in sensor and processor!"); @@ -335,7 +335,7 @@ ProcessorBasePtr Problem::installProcessor(const std::string& _prc_type, // return prc_ptr; } -SensorBasePtr Problem::getSensor(const std::string& _sensor_name) const +SensorBasePtr Problem::findSensor(const std::string& _sensor_name) const { auto sen_it = std::find_if(getHardware()->getSensorList().begin(), getHardware()->getSensorList().end(), @@ -350,6 +350,16 @@ SensorBasePtr Problem::getSensor(const std::string& _sensor_name) const return (*sen_it); } +ProcessorBasePtr Problem::findProcessor(const std::string& _processor_name) const +{ + for (const auto& sensor : getHardware()->getSensorList()) + for (const auto& processor : sensor->getProcessorList()) + if (processor->getName() == _processor_name) + return processor; + return nullptr; +} + + FrameBasePtr Problem::emplaceFrame(const TimeStamp& _time_stamp, // const StateStructure& _frame_structure, // const SizeEigen _dim, // diff --git a/src/processor/track_matrix.cpp b/src/processor/track_matrix.cpp index 1830270b13d7fea4d6462f2c97c7977b0879308f..d7154a788b5727b6e2f8cd201b382643110d5bf1 100644 --- a/src/processor/track_matrix.cpp +++ b/src/processor/track_matrix.cpp @@ -244,4 +244,14 @@ Track TrackMatrix::trackAtKeyframes(size_t _track_id) const return Track(); } +list<size_t> TrackMatrix::trackIds() const +{ + list<size_t> track_ids; + for (auto track : tracks_) + { + track_ids.push_back(track.first); + } + return track_ids; +} + } diff --git a/test/gtest_tree_manager_sliding_window_dual_rate.cpp b/test/gtest_tree_manager_sliding_window_dual_rate.cpp index e394a7c59279bb4d0e52c94b7eef479406ce5797..448fc0d93d27e1db1ee76c6ae46223be81a3c505 100644 --- a/test/gtest_tree_manager_sliding_window_dual_rate.cpp +++ b/test/gtest_tree_manager_sliding_window_dual_rate.cpp @@ -1050,11 +1050,11 @@ TEST(TreeManagerSlidingWindowDualRate, slidingWindowWithProcessor) TimeStamp t(0.0); double dt = 1; CaptureMotionPtr capture = std::make_shared<CaptureOdom3d>(t, - problem->getSensor("odom"), + problem->findSensor("odom"), data, data_cov); CaptureMotionPtr capture_bl = std::make_shared<CaptureOdom3d>(t, - problem_bl->getSensor("odom"), + problem_bl->findSensor("odom"), data, data_cov);