diff --git a/demos/processor_visual_odometry.yaml b/demos/processor_visual_odometry.yaml index 1eb9dbf40f8f465c32440ad359a6143a03aa032c..b586000d424ab57f11b5f070ff6c2733d138c898 100644 --- a/demos/processor_visual_odometry.yaml +++ b/demos/processor_visual_odometry.yaml @@ -1,31 +1,39 @@ -# ProcessorBase and ProcessorTracker parameters time_tolerance: 0.005 keyframe_vote: voting_active: true - min_features_for_keyframe: 42 # not used + # Trigger a new keyframe creation as well as detection of new keypoints in last frame + # when the track number goes below min_features_for_keyframe in incoming + min_features_for_keyframe: 10 +#Â Use a robust cost function apply_loss_function: true -# ProcessorTracker -max_new_features: 42 # not used +# Select the best new Keypoints when performing detection +max_new_features: 100 -# ProcessorBase parameters +#################################### +# ProcessorVisualOdometry parameters +# FAST KeyPoint detection +fast_params: + # Threshold on the keypoint pixel intensity (in uchar [0-255]) + # the higher, the more selective the detector is + threshold_fast: 50 + # Avoids getting multiple keypoints at the same place + non_max_suppresion: true + +# Lucas Kanade tracking parameters klt_params: patch_width: 15 patch_height: 15 nlevels_pyramids: 3 klt_max_err: 0.3 -fast_params: - threshold_fast: 50 - non_max_suppresion: true - -min_nb_tracks: 10 +# Keep the number of tracks below max_nb_tracks: 20 +# standard deviation of the pixel reprojection factor std_pix: 1 +# before creating a landmark, wait until the track is old enough min_track_length_for_landmark: 3 - -max_new_detections: 100 diff --git a/include/vision/processor/processor_visual_odometry.h b/include/vision/processor/processor_visual_odometry.h index 768ea232237ad4bb4b5a10570a93b31c74a0b1f2..49a5201efbcbde4c0da1401a155685ee334a9d68 100644 --- a/include/vision/processor/processor_visual_odometry.h +++ b/include/vision/processor/processor_visual_odometry.h @@ -71,8 +71,6 @@ struct ParamsProcessorVisualOdometry : public ParamsProcessorTracker double std_pix_; KltParams klt_params_; FastParams fast_params_; - unsigned int max_new_detections_; - unsigned int min_nb_tracks_; unsigned int max_nb_tracks_; unsigned int min_track_length_for_landmark_; @@ -91,8 +89,6 @@ struct ParamsProcessorVisualOdometry : public ParamsProcessorTracker fast_params_.threshold_fast_ = _server.getParam<int>( prefix + _unique_name + "/fast_params/threshold_fast"); fast_params_.non_max_suppresion_ = _server.getParam<bool>(prefix + _unique_name + "/fast_params/non_max_suppresion"); - max_new_detections_ = _server.getParam<unsigned int>(prefix + _unique_name + "/max_new_detections"); - min_nb_tracks_ = _server.getParam<unsigned int>(prefix + _unique_name + "/min_nb_tracks"); max_nb_tracks_ = _server.getParam<unsigned int>(prefix + _unique_name + "/max_nb_tracks"); min_track_length_for_landmark_ = _server.getParam<unsigned int>(prefix + _unique_name + "/min_track_length_for_landmark"); @@ -106,7 +102,6 @@ struct ParamsProcessorVisualOdometry : public ParamsProcessorTracker + "klt_params_.nlevels_pyramids_: " + std::to_string(klt_params_.nlevels_pyramids_) + "\n" + "fast_params_.threshold_fast_ : " + std::to_string(fast_params_.threshold_fast_) + "\n" + "fast_params_.non_max_suppresion_: " + std::to_string(fast_params_.non_max_suppresion_) + "\n" - + "min_nb_tracks_: " + std::to_string(min_nb_tracks_) + "\n" + "max_nb_tracks_: " + std::to_string(max_nb_tracks_) + "\n" + "min_track_length_for_landmark_: " + std::to_string(min_track_length_for_landmark_) + "\n"; } diff --git a/src/processor/processor_visual_odometry.cpp b/src/processor/processor_visual_odometry.cpp index 6c25c15cdf7b396991d8d8f76693629f92f11259..f42814743a7a5dd994b9e3237fd7d0a167e06727 100644 --- a/src/processor/processor_visual_odometry.cpp +++ b/src/processor/processor_visual_odometry.cpp @@ -86,7 +86,7 @@ void ProcessorVisualOdometry::preProcess() detector_->detect(img_incoming, kps_current); // Select a limited number of these keypoints - cv::KeyPointsFilter::retainBest(kps_current, params_visual_odometry_->max_new_detections_); + cv::KeyPointsFilter::retainBest(kps_current, params_visual_odometry_->max_new_features); capture_image_incoming_->addKeyPoints(kps_current); // Initialize the tracks data structure with a "dummy track" where the keypoint is pointing to itself @@ -157,13 +157,13 @@ void ProcessorVisualOdometry::preProcess() // detect new KeyPoints in last and track them to incoming //////////////////////////////// size_t n_tracks_origin = tracks_origin_incoming.size(); - if (n_tracks_origin < params_visual_odometry_->min_nb_tracks_){ + if (n_tracks_origin < params_visual_odometry_->min_features_for_keyframe){ std::cout << " Too Few Tracks" << std::endl; // Detect new KeyPoints std::vector<cv::KeyPoint> kps_last_new; detector_->detect(img_last, kps_last_new); - cv::KeyPointsFilter::retainBest(kps_last_new, params_visual_odometry_->max_new_detections_); + cv::KeyPointsFilter::retainBest(kps_last_new, params_visual_odometry_->max_new_features); // Create a map of wolf KeyPoints to track only the new ones KeyPointsMap mwkps_last_new, mwkps_incoming_new; @@ -181,6 +181,8 @@ void ProcessorVisualOdometry::preProcess() // Concatenation of old tracks and new tracks // Only keep tracks until it reaches a max nb of tracks + // TODO: the strategy for keeping the best new tracks is dumb + // -> should be improved for a better spatial repartition unsigned int count_new_tracks = 0; for (auto & track: tracks_last_incoming_new){ if ((n_tracks_origin + count_new_tracks) >= params_visual_odometry_->max_nb_tracks_){ diff --git a/test/gtest_processor_visual_odometry.cpp b/test/gtest_processor_visual_odometry.cpp index 6a2cfa10ccd1c6e177424de247b76e851dcb12ff..dcf4e4a25653045a5d42fc46174491d583afc377 100644 --- a/test/gtest_processor_visual_odometry.cpp +++ b/test/gtest_processor_visual_odometry.cpp @@ -147,7 +147,7 @@ TEST(ProcessorVisualOdometry, preProcess) params->klt_params_.criteria_ = cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 30, 0.01); params->fast_params_.threshold_fast_ = 20; params->fast_params_.non_max_suppresion_ = true; - params->min_nb_tracks_ = 50; + params->min_features_for_keyframe = 50; params->max_nb_tracks_ = 400; params->min_track_length_for_landmark_ = 4; ProcessorVisualOdometryTest processor(params); diff --git a/test/processor_visual_odometry_gtest.yaml b/test/processor_visual_odometry_gtest.yaml index 8d0064d8ebc56fe870c989c109205bec1c484973..b586000d424ab57f11b5f070ff6c2733d138c898 100644 --- a/test/processor_visual_odometry_gtest.yaml +++ b/test/processor_visual_odometry_gtest.yaml @@ -1,31 +1,39 @@ -# ProcessorBase and ProcessorTracker parameters time_tolerance: 0.005 keyframe_vote: voting_active: true - min_features_for_keyframe: 42 # not used + # Trigger a new keyframe creation as well as detection of new keypoints in last frame + # when the track number goes below min_features_for_keyframe in incoming + min_features_for_keyframe: 10 +#Â Use a robust cost function apply_loss_function: true -# ProcessorTracker -max_new_features: 42 # not used +# Select the best new Keypoints when performing detection +max_new_features: 100 -# ProcessorBase parameters +#################################### +# ProcessorVisualOdometry parameters +# FAST KeyPoint detection +fast_params: + # Threshold on the keypoint pixel intensity (in uchar [0-255]) + # the higher, the more selective the detector is + threshold_fast: 50 + # Avoids getting multiple keypoints at the same place + non_max_suppresion: true + +# Lucas Kanade tracking parameters klt_params: patch_width: 15 patch_height: 15 nlevels_pyramids: 3 klt_max_err: 0.3 -fast_params: - threshold_fast: 50 - non_max_suppresion: true - -min_nb_tracks: 100 -max_nb_tracks: 200 +# Keep the number of tracks below +max_nb_tracks: 20 +# standard deviation of the pixel reprojection factor std_pix: 1 +# before creating a landmark, wait until the track is old enough min_track_length_for_landmark: 3 - -max_new_detections: 100