Skip to content

Commit

Permalink
Merge pull request MIT-SPARK#100 from Wallbraker/opencv-4-and-warning…
Browse files Browse the repository at this point in the history
…-fixes

Enable building with OpenCV 3 & 4, along with some warning fixes
  • Loading branch information
ToniRV authored Sep 5, 2020
2 parents ec6a327 + 8ceccdc commit 40fff93
Show file tree
Hide file tree
Showing 17 changed files with 71 additions and 37 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ find_package(Gflags REQUIRED)
find_package(Glog 0.3.5 REQUIRED)
find_package(GTSAM REQUIRED)
find_package(opengv REQUIRED)
find_package(OpenCV 3.3.1 REQUIRED)
find_package(OpenCV REQUIRED)
find_package(DBoW2 REQUIRED)
if(NOT TARGET DBoW2::DBoW2)
add_library(DBoW2::DBoW2 INTERFACE IMPORTED)
Expand Down
2 changes: 1 addition & 1 deletion include/kimera-vio/frontend/CameraParams.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,11 +53,11 @@ class CameraParams : public PipelineParams {
camera_id_(),
camera_model_(),
intrinsics_(),
K_(),
body_Pose_cam_(),
frame_rate_(),
image_size_(),
calibration_(),
K_(),
distortion_model_(),
distortion_coeff_(),
distortion_coeff_mat_(),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,8 @@ struct FrontendOutput : public PipelinePayload {
stereo_frame_lkf_(stereo_frame_lkf),
pim_(pim),
imu_acc_gyrs_(imu_acc_gyrs),
feature_tracks_(feature_tracks),
debug_tracker_info_(debug_tracker_info) {}
debug_tracker_info_(debug_tracker_info),
feature_tracks_(feature_tracks) {}

virtual ~FrontendOutput() = default;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,9 @@ struct SubPixelCornerFinderParams : public PipelineParams {
/// Termination criteria defined in terms of change in error and maximum
/// number of iterations
cv::TermCriteria term_criteria_ =
cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 10, 0.01);
cv::TermCriteria(cv::TermCriteria::EPS + cv::TermCriteria::COUNT,
10,
0.01);
cv::Size window_size_ = cv::Size(10, 10);
cv::Size zero_zone_ = cv::Size(-1, -1);
};
Expand Down
6 changes: 3 additions & 3 deletions include/kimera-vio/logging/Logger.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,9 @@ namespace VIO {

/* -------------------------------------------------------------------------- */
// Open files with name output_filename, and checks that it is valid
static void OpenFile(const std::string& output_filename,
std::ofstream* output_file,
bool append_mode = false) {
static inline void OpenFile(const std::string& output_filename,
std::ofstream* output_file,
bool append_mode = false) {
CHECK_NOTNULL(output_file);
output_file->open(output_filename.c_str(),
append_mode ? std::ios_base::app : std::ios_base::out);
Expand Down
13 changes: 5 additions & 8 deletions include/kimera-vio/loopclosure/LoopClosureDetector.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,20 +14,17 @@

#pragma once

#include <DBoW2/DBoW2.h>
#include <gtsam/geometry/Pose3.h>
#include <gtsam/linear/NoiseModel.h>

#include <limits>
#include <memory>
#include <opencv2/opencv.hpp>
#include <unordered_map>
#include <utility>
#include <vector>

#include <gtsam/geometry/Pose3.h>
#include <gtsam/linear/NoiseModel.h>

#include <opencv/cv.hpp>
#include <opencv2/features2d.hpp>

#include <DBoW2/DBoW2.h>

#include "kimera-vio/frontend/StereoFrame.h"
#include "kimera-vio/logging/Logger.h"
#include "kimera-vio/loopclosure/LcdThirdPartyWrapper.h"
Expand Down
19 changes: 18 additions & 1 deletion include/kimera-vio/loopclosure/LoopClosureDetectorParams.h
Original file line number Diff line number Diff line change
Expand Up @@ -63,15 +63,24 @@ class LoopClosureDetectorParams : public PipelineParams {
bool use_mono_rot = true,

double lowe_ratio = 0.7,
int matcher_type = 4,
#if CV_VERSION_MAJOR == 3
int matcher_type = cv::DescriptorMatcher::BRUTEFORCE_HAMMING,
#else
cv::DescriptorMatcher::MatcherType matcher_type =
cv::DescriptorMatcher::MatcherType::BRUTEFORCE_HAMMING,
#endif

int nfeatures = 500,
float scale_factor = 1.2f,
int nlevels = 8,
int edge_threshold = 31,
int first_level = 0,
int WTA_K = 2,
#if CV_VERSION_MAJOR == 3
int score_type = cv::ORB::HARRIS_SCORE,
#else
cv::ORB::ScoreType score_type = cv::ORB::ScoreType::HARRIS_SCORE,
#endif
int patch_sze = 31,
int fast_threshold = 20,

Expand Down Expand Up @@ -182,7 +191,11 @@ class LoopClosureDetectorParams : public PipelineParams {

///////////////////////// ORB feature matching params ////////////////////////
double lowe_ratio_;
#if CV_VERSION_MAJOR == 3
int matcher_type_;
#else
cv::DescriptorMatcher::MatcherType matcher_type_;
#endif
//////////////////////////////////////////////////////////////////////////////

///////////////////////// ORB feature detector params ////////////////////////
Expand All @@ -192,7 +205,11 @@ class LoopClosureDetectorParams : public PipelineParams {
int edge_threshold_;
int first_level_;
int WTA_K_;
#if CV_VERSION_MAJOR == 3
int score_type_;
#else
cv::ORB::ScoreType score_type_;
#endif
int patch_sze_;
int fast_threshold_;
//////////////////////////////////////////////////////////////////////////////
Expand Down
4 changes: 2 additions & 2 deletions include/kimera-vio/utils/ThreadsafeQueue.h
Original file line number Diff line number Diff line change
Expand Up @@ -257,8 +257,8 @@ class ThreadsafeNullQueue : public ThreadsafeQueue<T> {

template <typename T>
ThreadsafeQueueBase<T>::ThreadsafeQueueBase(const std::string& queue_id)
: mutex_(),
queue_id_(queue_id),
: queue_id_(queue_id),
mutex_(),
data_queue_(),
data_cond_(),
shutdown_(false) {}
Expand Down
3 changes: 2 additions & 1 deletion src/dataprovider/KittiDataProvider.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ KittiDataProvider::KittiDataProvider()
}

cv::Mat KittiDataProvider::readKittiImage(const std::string& img_name) {
cv::Mat img = cv::imread(img_name, CV_LOAD_IMAGE_UNCHANGED);
cv::Mat img = cv::imread(img_name, cv::ImreadModes::IMREAD_UNCHANGED);
LOG_IF(FATAL, img.empty()) << "Failed to load image: " << img_name;
// cv::imshow("check", img);
// cv::waitKey(0);
Expand Down Expand Up @@ -205,6 +205,7 @@ bool Earlier_time_imu(std::pair<Timestamp, int>& a,

bool KittiDataProvider::parseImuData(const std::string& input_dataset_path,
KittiData* kitti_data) {
return false;
}

/* -------------------------------------------------------------------------- */
Expand Down
2 changes: 1 addition & 1 deletion src/frontend/StereoFrame.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1278,7 +1278,7 @@ std::pair<StatusKeypointCV, double> StereoFrame::findMatchingKeypointRectified(
// Refine keypoint with subpixel accuracy.
if (sparse_stereo_params_.subpixel_refinement_) {
static const cv::TermCriteria criteria(
CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 40, 0.001);
cv::TermCriteria::EPS + cv::TermCriteria::COUNT, 40, 0.001);
static const cv::Size winSize(10, 10);
static const cv::Size zeroZone(-1, -1);
std::vector<cv::Point2f> corner;
Expand Down
5 changes: 5 additions & 0 deletions src/frontend/feature-detector/FeatureDetector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,12 @@ FeatureDetector::FeatureDetector(
10; // Very small bcs we don't use descriptors (yet).
static constexpr int first_level = 0;
static constexpr int WTA_K = 0; // We don't use descriptors (yet).
#if CV_VERSION_MAJOR == 3
static constexpr int score_type = cv::ORB::HARRIS_SCORE;
#else
static constexpr cv::ORB::ScoreType score_type =
cv::ORB::ScoreType::HARRIS_SCORE;
#endif
static constexpr int patch_size = 0; // We don't use descriptors (yet).
feature_detector_ =
cv::ORB::create(feature_detector_params_.max_features_per_frame_,
Expand Down
4 changes: 3 additions & 1 deletion src/frontend/feature-detector/FeatureDetectorParams.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ void SubPixelCornerFinderParams::print() const {

bool SubPixelCornerFinderParams::parseYAML(const std::string& filepath) {
YamlParser yaml_parser(filepath);
term_criteria_.type = CV_TERMCRIT_EPS + CV_TERMCRIT_ITER;
term_criteria_.type = cv::TermCriteria::EPS + cv::TermCriteria::COUNT;
yaml_parser.getYamlParam("max_iters", &term_criteria_.maxCount);
yaml_parser.getYamlParam("epsilon_error", &term_criteria_.epsilon);
int window_size = 0;
Expand Down Expand Up @@ -176,6 +176,8 @@ bool FeatureDetectorParams::parseYAML(const std::string& filepath) {

// FAST specific params
yaml_parser.getYamlParam("fast_thresh", &fast_thresh_);

return true;
}

bool FeatureDetectorParams::equals(const FeatureDetectorParams& tp2,
Expand Down
2 changes: 1 addition & 1 deletion src/frontend/feature-detector/NonMaximumSuppression.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ std::vector<cv::KeyPoint> AdaptiveNonMaximumSuppression::suppressNonMax(
}
std::vector<int> Indx(responseVector.size());
std::iota(std::begin(Indx), std::end(Indx), 0);
cv::sortIdx(responseVector, Indx, CV_SORT_DESCENDING);
cv::sortIdx(responseVector, Indx, cv::SortFlags::SORT_DESCENDING);
std::vector<cv::KeyPoint> keyPointsSorted;
for (unsigned int i = 0; i < keyPoints.size(); i++) {
keyPointsSorted.push_back(keyPoints[Indx[i]]);
Expand Down
14 changes: 13 additions & 1 deletion src/loopclosure/LoopClosureDetectorParams.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,15 +50,23 @@ LoopClosureDetectorParams::LoopClosureDetectorParams(
bool use_mono_rot,

double lowe_ratio,
#if CV_VERSION_MAJOR == 3
int matcher_type,
#else
cv::DescriptorMatcher::MatcherType matcher_type,
#endif

int nfeatures,
float scale_factor,
int nlevels,
int edge_threshold,
int first_level,
int WTA_K,
#if CV_VERSION_MAJOR == 3
int score_type,
#else
cv::ORB::ScoreType score_type,
#endif
int patch_sze,
int fast_threshold,

Expand Down Expand Up @@ -194,7 +202,11 @@ bool LoopClosureDetectorParams::parseYAML(const std::string& filepath) {
yaml_parser.getYamlParam("score_type_id", &score_type_id);
switch (score_type_id) {
case 0:
#if CV_VERSION_MAJOR == 3
score_type_ = cv::ORB::HARRIS_SCORE;
#else
score_type_ = cv::ORB::ScoreType::HARRIS_SCORE;
#endif
break;
// TODO(marcus): add the rest of the options here
default:
Expand Down Expand Up @@ -296,7 +308,7 @@ void LoopClosureDetectorParams::print() const {
"WTA_K_: ",
WTA_K_,
"score_type_: ",
score_type_,
static_cast<unsigned int>(score_type_),
"patch_sze_: ",
patch_sze_,
"fast_threshold_: ",
Expand Down
2 changes: 0 additions & 2 deletions src/pipeline/Pipeline-definitions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,6 @@
* @author Antoni Rosinol
*/

#pragma once

#include "kimera-vio/pipeline/Pipeline-definitions.h"

#include "kimera-vio/backend/RegularVioBackEndParams.h"
Expand Down
20 changes: 10 additions & 10 deletions src/pipeline/Pipeline.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,28 +71,28 @@ namespace VIO {
Pipeline::Pipeline(const VioParams& params,
Visualizer3D::UniquePtr&& visualizer,
DisplayBase::UniquePtr&& displayer)
: backend_type_(static_cast<BackendType>(params.backend_type_)),
: backend_params_(params.backend_params_),
frontend_params_(params.frontend_params_),
imu_params_(params.imu_params_),
backend_type_(static_cast<BackendType>(params.backend_type_)),
parallel_run_(params.parallel_run_),
stereo_camera_(nullptr),
data_provider_module_(nullptr),
vio_frontend_module_(nullptr),
stereo_frontend_input_queue_("stereo_frontend_input_queue"),
vio_backend_module_(nullptr),
lcd_module_(nullptr),
backend_params_(params.backend_params_),
frontend_params_(params.frontend_params_),
imu_params_(params.imu_params_),
backend_input_queue_("backend_input_queue"),
mesher_module_(nullptr),
lcd_module_(nullptr),
visualizer_module_(nullptr),
display_input_queue_("display_input_queue"),
display_module_(nullptr),
shutdown_pipeline_cb_(nullptr),
frontend_thread_(nullptr),
backend_thread_(nullptr),
mesher_thread_(nullptr),
lcd_thread_(nullptr),
visualizer_thread_(nullptr),
parallel_run_(params.parallel_run_),
stereo_frontend_input_queue_("stereo_frontend_input_queue"),
backend_input_queue_("backend_input_queue"),
display_input_queue_("display_input_queue") {
visualizer_thread_(nullptr) {
if (FLAGS_deterministic_random_number_generator) {
setDeterministicPipeline();
}
Expand Down
2 changes: 1 addition & 1 deletion tests/testFeatureDetectorParams.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ TEST(testFeatureDetectorParams, FeatureDetectorParamParseYAML) {

SubPixelCornerFinderParams expected_subpixel_params;
expected_subpixel_params.term_criteria_.type =
CV_TERMCRIT_EPS + CV_TERMCRIT_ITER;
cv::TermCriteria::EPS + cv::TermCriteria::COUNT;
expected_subpixel_params.term_criteria_.maxCount = 42;
expected_subpixel_params.term_criteria_.epsilon = 0.201;
expected_subpixel_params.window_size_ = cv::Size(12, 12);
Expand Down

0 comments on commit 40fff93

Please sign in to comment.