Skip to content

Commit

Permalink
Descriptor based tracking
Browse files Browse the repository at this point in the history
  • Loading branch information
raphaelchang committed Oct 8, 2019
1 parent 96f7f79 commit 858f569
Show file tree
Hide file tree
Showing 38 changed files with 362 additions and 91 deletions.
3 changes: 2 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ project(omni_slam_eval)
set(CMAKE_VERBOSE_MAKEFILE FALSE)

if (NOT CMAKE_BUILD_TYPE)
set(CMAKE_BUILD_TYPE "RelWithDebInfo" CACHE STRING "Choose the type of build, options are: Debug Release RelWithDebInfo MinSizeRel." FORCE)
set(CMAKE_BUILD_TYPE "Release" CACHE STRING "Choose the type of build, options are: Debug Release RelWithDebInfo MinSizeRel." FORCE)
endif (NOT CMAKE_BUILD_TYPE)

# find catkin dependencies
Expand Down Expand Up @@ -65,6 +65,7 @@ add_library(omni_slam_eval_lib
src/data/landmark.cc
src/feature/tracker.cc
src/feature/lk_tracker.cc
src/feature/descriptor_tracker.cc
src/feature/detector.cc
src/feature/matcher.cc
src/reconstruction/triangulator.cc
Expand Down
3 changes: 3 additions & 0 deletions launch/odometry_eval.launch
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,8 @@
camera_parameters: $(arg camera_params)
detector_type: 'GFTT'
detector_parameters: {maxCorners: 2000, qualityLevel: 0.001, minDistance: 5, blockSize: 5}
keyframe_interval: 1
tracker_type: 'lk'
tracker_window_size: 128
tracker_num_scales: 4
tracker_checker_epipolar_threshold: 0.008
Expand All @@ -33,6 +35,7 @@
tracker_template_update_rate: 1
min_features_per_region: 100
max_features_per_region: 1000
odometry_type: 'pnp'
pnp_inlier_threshold: 3.0
pnp_iterations: 3000
bundle_adjustment_max_iterations: 1000
Expand Down
3 changes: 2 additions & 1 deletion launch/reconstruction_eval.launch
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,14 @@
camera_parameters: $(arg camera_params)
detector_type: 'GFTT'
detector_parameters: {maxCorners: 5000, qualityLevel: 0.001, minDistance: 5, blockSize: 5}
keyframe_interval: 1
tracker_type: 'lk'
tracker_window_size: 128
tracker_num_scales: 4
tracker_checker_epipolar_threshold: 0.008
tracker_checker_iterations: 1000
tracker_delta_pixel_error_threshold: 0.0
tracker_error_threshold: 20.0
tracker_template_update_rate: 1
min_features_per_region: 10
max_features_per_region: 5000
max_reprojection_error: 5.0
Expand Down
6 changes: 4 additions & 2 deletions launch/slam_eval.launch
Original file line number Diff line number Diff line change
Expand Up @@ -29,15 +29,17 @@
stereo_camera_parameters: $(arg stereo_camera_params)
detector_type: 'GFTT'
detector_parameters: {maxCorners: 5000, qualityLevel: 0.001, minDistance: 5, blockSize: 5}
keyframe_interval: 1
tracker_type: 'lk'
tracker_window_size: 128
tracker_num_scales: 4
tracker_checker_epipolar_threshold: 0.008
tracker_checker_iterations: 1000
tracker_delta_pixel_error_threshold: 0.0
tracker_error_threshold: 20.0
tracker_template_update_rate: 1
tracker_error_threshold: 128
min_features_per_region: 100
max_features_per_region: 1000
odometry_type: 'pnp'
pnp_inlier_threshold: 3.0
pnp_iterations: 3000
max_reprojection_error: 5.0
Expand Down
4 changes: 3 additions & 1 deletion launch/slam_eval_kitti.launch
Original file line number Diff line number Diff line change
Expand Up @@ -29,15 +29,17 @@
stereo_camera_parameters: $(arg stereo_camera_params)
detector_type: 'GFTT'
detector_parameters: {maxCorners: 5000, qualityLevel: 0.001, minDistance: 5, blockSize: 5}
keyframe_interval: 1
tracker_type: 'lk'
tracker_window_size: 128
tracker_num_scales: 4
tracker_checker_epipolar_threshold: 0.008
tracker_checker_iterations: 1000
tracker_delta_pixel_error_threshold: 0.0
tracker_error_threshold: 20.0
tracker_template_update_rate: 1
min_features_per_region: 100
max_features_per_region: 1000
odometry_type: 'pnp'
pnp_inlier_threshold: 3.0
pnp_iterations: 3000
max_reprojection_error: 2.0
Expand Down
4 changes: 3 additions & 1 deletion launch/slam_eval_t265.launch
Original file line number Diff line number Diff line change
Expand Up @@ -29,15 +29,17 @@
stereo_camera_parameters: $(arg stereo_camera_params)
detector_type: 'GFTT'
detector_parameters: {maxCorners: 5000, qualityLevel: 0.001, minDistance: 5, blockSize: 5}
keyframe_interval: 1
tracker_type: 'lk'
tracker_window_size: 128
tracker_num_scales: 4
tracker_checker_epipolar_threshold: 0.008
tracker_checker_iterations: 1000
tracker_delta_pixel_error_threshold: 0.0
tracker_error_threshold: 20.0
tracker_template_update_rate: 1
min_features_per_region: 100
max_features_per_region: 1000
odometry_type: 'pnp'
pnp_inlier_threshold: 3.0
pnp_iterations: 3000
max_reprojection_error: 5.0
Expand Down
9 changes: 6 additions & 3 deletions launch/slam_eval_tum.launch
Original file line number Diff line number Diff line change
Expand Up @@ -27,17 +27,20 @@
camera_model: '$(arg camera_model)'
camera_parameters: $(arg camera_params)
stereo_camera_parameters: $(arg stereo_camera_params)
detector_type: 'GFTT'
detector_parameters: {maxCorners: 5000, qualityLevel: 0.001, minDistance: 5, blockSize: 5}
detector_type: 'ORB'
detector_parameters: {nfeatures: 1000}
descriptor_type: 'ORB'
keyframe_interval: 1
tracker_type: 'descriptor'
tracker_window_size: 128
tracker_num_scales: 4
tracker_checker_epipolar_threshold: 0.008
tracker_checker_iterations: 1000
tracker_delta_pixel_error_threshold: 0.0
tracker_error_threshold: 1000000.0
tracker_template_update_rate: 1
min_features_per_region: 10
max_features_per_region: 1000
odometry_type: 'pnp'
pnp_inlier_threshold: 3.0
pnp_iterations: 3000
max_reprojection_error: 5.0
Expand Down
3 changes: 2 additions & 1 deletion launch/tracking_eval.launch
Original file line number Diff line number Diff line change
Expand Up @@ -17,15 +17,16 @@
camera_parameters: $(arg camera_params)
detector_type: 'GFTT'
detector_parameters: {maxCorners: 100, qualityLevel: 0.01, minDistance: 5, blockSize: 5}
tracker_type: 'lk'
tracker_window_size: 128
tracker_num_scales: 4
tracker_checker_epipolar_threshold: 0.008
tracker_checker_iterations: 1000
tracker_delta_pixel_error_threshold: 3.0
tracker_error_threshold: 20.0
tracker_template_update_rate: 1
min_features_per_region: 10
max_features_per_region: 999999
keyframe_interval: 1
</rosparam>
</node>
</launch>
5 changes: 5 additions & 0 deletions src/data/feature.cc
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,11 @@ const cv::Mat& Feature::GetDescriptor() const
return descriptor_;
}

void Feature::SetDescriptor(const cv::Mat& descriptor)
{
descriptor_ = descriptor.clone();
}

Vector3d Feature::GetBearing() const
{
Vector3d cameraFramePt;
Expand Down
2 changes: 2 additions & 0 deletions src/data/feature.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@ class Feature
const cv::KeyPoint& GetKeypoint() const;
const cv::Mat& GetDescriptor() const;

void SetDescriptor(const cv::Mat& descriptor);

Vector3d GetBearing() const;
Vector3d GetWorldPoint();
Vector3d GetEstimatedWorldPoint();
Expand Down
18 changes: 18 additions & 0 deletions src/data/landmark.cc
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,15 @@ const Feature* Landmark::GetObservationByFrameID(const int frame_id) const
return &obs_[idToIndex_.at(frame_id)];
}

Feature* Landmark::GetObservationByFrameID(const int frame_id)
{
if (idToIndex_.find(frame_id) == idToIndex_.end())
{
return nullptr;
}
return &obs_[idToIndex_.at(frame_id)];
}

const Feature* Landmark::GetStereoObservationByFrameID(const int frame_id) const
{
if (idToStereoIndex_.find(frame_id) == idToStereoIndex_.end())
Expand All @@ -124,6 +133,15 @@ const Feature* Landmark::GetStereoObservationByFrameID(const int frame_id) const
return &stereoObs_[idToStereoIndex_.at(frame_id)];
}

Feature* Landmark::GetStereoObservationByFrameID(const int frame_id)
{
if (idToStereoIndex_.find(frame_id) == idToStereoIndex_.end())
{
return nullptr;
}
return &stereoObs_[idToStereoIndex_.at(frame_id)];
}

void Landmark::SetEstimatedPosition(const Vector3d &pos, const std::vector<int> &frame_ids)
{
posEstimate_ = pos;
Expand Down
2 changes: 2 additions & 0 deletions src/data/landmark.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,9 @@ class Landmark
const int GetFirstFrameID() const;
const int GetNumObservations() const;
const Feature* GetObservationByFrameID(const int frame_id) const;
Feature* GetObservationByFrameID(const int frame_id);
const Feature* GetStereoObservationByFrameID(const int frame_id) const;
Feature* GetStereoObservationByFrameID(const int frame_id);
void SetEstimatedPosition(const Vector3d &pos, const std::vector<int> &frame_ids);
void SetEstimatedPosition(const Vector3d &pos);

Expand Down
88 changes: 88 additions & 0 deletions src/feature/descriptor_tracker.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,88 @@
#include "descriptor_tracker.h"
#include "util/tf_util.h"

namespace omni_slam
{
namespace feature
{

DescriptorTracker::DescriptorTracker(std::string detector_type, std::string descriptor_type, std::map<std::string, double> det_args, std::map<std::string, double> desc_args, const float match_thresh, const int keyframe_interval)
: Tracker(keyframe_interval),
Matcher(descriptor_type, match_thresh),
Detector(detector_type, descriptor_type, det_args, desc_args)
{
}

int DescriptorTracker::DoTrack(std::vector<data::Landmark> &landmarks, data::Frame &cur_frame, std::vector<double> &errors, bool stereo)
{
std::vector<data::Landmark> curLandmarks;
std::vector<data::Landmark> prevLandmarks;
int imsize = std::max(cur_frame.GetImage().rows, cur_frame.GetImage().cols);
#pragma omp parallel for collapse(2)
for (int i = 0; i < Region::rs.size() - 1; i++)
{
for (int j = 0; j < Region::ts.size() - 1; j++)
{
feature::Detector detector(*static_cast<Detector*>(this));
detector.DetectInRadialRegion(cur_frame, curLandmarks, feature::Region::rs[i] * imsize, feature::Region::rs[i+1] * imsize, feature::Region::ts[j], feature::Region::ts[j+1]);
detector.DetectInRadialRegion(cur_frame, curLandmarks, feature::Region::rs[i] * imsize, feature::Region::rs[i+1] * imsize, feature::Region::ts[j], feature::Region::ts[j+1], true);
}
}
std::vector<int> origInx;
int i = 0;
for (const data::Landmark &landmark : landmarks)
{
if (landmark.IsObservedInFrame(keyframeId_))
{
data::Landmark l;
l.AddObservation(*landmark.GetObservationByFrameID(keyframeId_), false);
if (stereo)
{
const data::Feature* stereoFeat = landmark.GetStereoObservationByFrameID(keyframeId_);
if (stereoFeat != nullptr)
{
l.AddStereoObservation(*stereoFeat);
}
}
prevLandmarks.push_back(l);
origInx.push_back(i);
}
i++;
}
std::vector<data::Landmark> matches;
std::vector<data::Landmark> stereoMatches;
std::vector<int> indices;
std::vector<std::vector<double>> distances;
std::vector<std::vector<double>> stereoDistances;
std::vector<int> stereoIndices;
Match(curLandmarks, prevLandmarks, matches, distances, indices, false);
if (stereo)
{
Match(curLandmarks, prevLandmarks, stereoMatches, stereoDistances, stereoIndices, true);
}
errors.clear();
int numGood = 0;
for (int i = 0; i < matches.size(); i++)
{
data::Landmark &landmark = landmarks[origInx[indices[i]]];
data::Feature feat(cur_frame, matches[i].GetObservationByFrameID(cur_frame.GetID())->GetKeypoint(), matches[i].GetObservationByFrameID(cur_frame.GetID())->GetDescriptor());
landmark.AddObservation(feat);
errors.push_back(distances[i][0]);
numGood++;
}
for (int i = 0; i < stereoMatches.size(); i++)
{
data::Landmark &landmark = landmarks[origInx[stereoIndices[i]]];
if (!landmark.IsObservedInFrame(cur_frame.GetID()))
{
continue;
}
data::Feature feat(cur_frame, stereoMatches[i].GetObservationByFrameID(cur_frame.GetID())->GetKeypoint(), stereoMatches[i].GetObservationByFrameID(cur_frame.GetID())->GetDescriptor(), true);
landmark.AddStereoObservation(feat);
}

return numGood;
}

}
}
30 changes: 30 additions & 0 deletions src/feature/descriptor_tracker.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
#ifndef _DESCRIPTOR_TRACKER_H_
#define _DESCRIPTOR_TRACKER_H_

#include "tracker.h"
#include "matcher.h"
#include "detector.h"
#include "region.h"
#include <opencv2/opencv.hpp>
#include "data/frame.h"
#include "data/landmark.h"
#include "odometry/five_point.h"
#include <vector>

namespace omni_slam
{
namespace feature
{

class DescriptorTracker : public Tracker, public Matcher, public Detector
{
public:
DescriptorTracker(std::string detector_type, std::string descriptor_type, std::map<std::string, double> det_args, std::map<std::string, double> desc_args, const float match_thresh = 0., const int keyframe_interval = 1);

private:
int DoTrack(std::vector<data::Landmark> &landmarks, data::Frame &cur_frame, std::vector<double> &errors, bool stereo);
};

}
}
#endif /* _DESCRIPTOR_TRACKER_H_ */
Loading

0 comments on commit 858f569

Please sign in to comment.