Skip to content
Snippets Groups Projects
Commit ff5047a4 authored by Mederic Fourmy's avatar Mederic Fourmy
Browse files

Removed useless parameters in processor yaml, added a lot of comments in the yaml

parent 65d1b9c1
No related branches found
No related tags found
2 merge requests!36After cmake and const refactor,!28Resolve "Building a new visual odometry system"
# ProcessorBase and ProcessorTracker parameters
time_tolerance: 0.005 time_tolerance: 0.005
keyframe_vote: keyframe_vote:
voting_active: true 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 apply_loss_function: true
# ProcessorTracker # Select the best new Keypoints when performing detection
max_new_features: 42 # not used 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: klt_params:
patch_width: 15 patch_width: 15
patch_height: 15 patch_height: 15
nlevels_pyramids: 3 nlevels_pyramids: 3
klt_max_err: 0.3 klt_max_err: 0.3
fast_params: # Keep the number of tracks below
threshold_fast: 50
non_max_suppresion: true
min_nb_tracks: 10
max_nb_tracks: 20 max_nb_tracks: 20
# standard deviation of the pixel reprojection factor
std_pix: 1 std_pix: 1
# before creating a landmark, wait until the track is old enough
min_track_length_for_landmark: 3 min_track_length_for_landmark: 3
max_new_detections: 100
...@@ -71,8 +71,6 @@ struct ParamsProcessorVisualOdometry : public ParamsProcessorTracker ...@@ -71,8 +71,6 @@ struct ParamsProcessorVisualOdometry : public ParamsProcessorTracker
double std_pix_; double std_pix_;
KltParams klt_params_; KltParams klt_params_;
FastParams fast_params_; FastParams fast_params_;
unsigned int max_new_detections_;
unsigned int min_nb_tracks_;
unsigned int max_nb_tracks_; unsigned int max_nb_tracks_;
unsigned int min_track_length_for_landmark_; unsigned int min_track_length_for_landmark_;
...@@ -91,8 +89,6 @@ struct ParamsProcessorVisualOdometry : public ParamsProcessorTracker ...@@ -91,8 +89,6 @@ struct ParamsProcessorVisualOdometry : public ParamsProcessorTracker
fast_params_.threshold_fast_ = _server.getParam<int>( prefix + _unique_name + "/fast_params/threshold_fast"); 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"); 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"); 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"); 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 ...@@ -106,7 +102,6 @@ struct ParamsProcessorVisualOdometry : public ParamsProcessorTracker
+ "klt_params_.nlevels_pyramids_: " + std::to_string(klt_params_.nlevels_pyramids_) + "\n" + "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_.threshold_fast_ : " + std::to_string(fast_params_.threshold_fast_) + "\n"
+ "fast_params_.non_max_suppresion_: " + std::to_string(fast_params_.non_max_suppresion_) + "\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" + "max_nb_tracks_: " + std::to_string(max_nb_tracks_) + "\n"
+ "min_track_length_for_landmark_: " + std::to_string(min_track_length_for_landmark_) + "\n"; + "min_track_length_for_landmark_: " + std::to_string(min_track_length_for_landmark_) + "\n";
} }
......
...@@ -86,7 +86,7 @@ void ProcessorVisualOdometry::preProcess() ...@@ -86,7 +86,7 @@ void ProcessorVisualOdometry::preProcess()
detector_->detect(img_incoming, kps_current); detector_->detect(img_incoming, kps_current);
// Select a limited number of these keypoints // 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); capture_image_incoming_->addKeyPoints(kps_current);
// Initialize the tracks data structure with a "dummy track" where the keypoint is pointing to itself // Initialize the tracks data structure with a "dummy track" where the keypoint is pointing to itself
...@@ -157,13 +157,13 @@ void ProcessorVisualOdometry::preProcess() ...@@ -157,13 +157,13 @@ void ProcessorVisualOdometry::preProcess()
// detect new KeyPoints in last and track them to incoming // detect new KeyPoints in last and track them to incoming
//////////////////////////////// ////////////////////////////////
size_t n_tracks_origin = tracks_origin_incoming.size(); 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; std::cout << " Too Few Tracks" << std::endl;
// Detect new KeyPoints // Detect new KeyPoints
std::vector<cv::KeyPoint> kps_last_new; std::vector<cv::KeyPoint> kps_last_new;
detector_->detect(img_last, 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 // Create a map of wolf KeyPoints to track only the new ones
KeyPointsMap mwkps_last_new, mwkps_incoming_new; KeyPointsMap mwkps_last_new, mwkps_incoming_new;
...@@ -181,6 +181,8 @@ void ProcessorVisualOdometry::preProcess() ...@@ -181,6 +181,8 @@ void ProcessorVisualOdometry::preProcess()
// Concatenation of old tracks and new tracks // Concatenation of old tracks and new tracks
// Only keep tracks until it reaches a max nb of 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; unsigned int count_new_tracks = 0;
for (auto & track: tracks_last_incoming_new){ for (auto & track: tracks_last_incoming_new){
if ((n_tracks_origin + count_new_tracks) >= params_visual_odometry_->max_nb_tracks_){ if ((n_tracks_origin + count_new_tracks) >= params_visual_odometry_->max_nb_tracks_){
......
...@@ -147,7 +147,7 @@ TEST(ProcessorVisualOdometry, preProcess) ...@@ -147,7 +147,7 @@ TEST(ProcessorVisualOdometry, preProcess)
params->klt_params_.criteria_ = cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 30, 0.01); params->klt_params_.criteria_ = cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 30, 0.01);
params->fast_params_.threshold_fast_ = 20; params->fast_params_.threshold_fast_ = 20;
params->fast_params_.non_max_suppresion_ = true; params->fast_params_.non_max_suppresion_ = true;
params->min_nb_tracks_ = 50; params->min_features_for_keyframe = 50;
params->max_nb_tracks_ = 400; params->max_nb_tracks_ = 400;
params->min_track_length_for_landmark_ = 4; params->min_track_length_for_landmark_ = 4;
ProcessorVisualOdometryTest processor(params); ProcessorVisualOdometryTest processor(params);
......
# ProcessorBase and ProcessorTracker parameters
time_tolerance: 0.005 time_tolerance: 0.005
keyframe_vote: keyframe_vote:
voting_active: true 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 apply_loss_function: true
# ProcessorTracker # Select the best new Keypoints when performing detection
max_new_features: 42 # not used 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: klt_params:
patch_width: 15 patch_width: 15
patch_height: 15 patch_height: 15
nlevels_pyramids: 3 nlevels_pyramids: 3
klt_max_err: 0.3 klt_max_err: 0.3
fast_params: # Keep the number of tracks below
threshold_fast: 50 max_nb_tracks: 20
non_max_suppresion: true
min_nb_tracks: 100
max_nb_tracks: 200
# standard deviation of the pixel reprojection factor
std_pix: 1 std_pix: 1
# before creating a landmark, wait until the track is old enough
min_track_length_for_landmark: 3 min_track_length_for_landmark: 3
max_new_detections: 100
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment