diff --git a/CMakeLists.txt b/CMakeLists.txt index 76084e5c..9e59bdb9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,11 +1,11 @@ -CMAKE_MINIMUM_REQUIRED(VERSION 3.2) +cmake_minimum_required(VERSION 3.16) PROJECT(wave) # Package version, used when other projects FIND_PACKAGE(wave ) -SET(WAVE_PACKAGE_VERSION 0.1.0) +SET(WAVE_PACKAGE_VERSION 0.1.1) # Compiler settings for all targets -SET(CMAKE_CXX_STANDARD 11) +SET(CMAKE_CXX_STANDARD 17) SET(CMAKE_POSITION_INDEPENDENT_CODE ON) ADD_COMPILE_OPTIONS(-Wall -Wextra -Wno-strict-overflow) @@ -42,7 +42,6 @@ IF(APPEND_OPT_WAVELAB) MESSAGE(STATUS "Adding /opt/wavelab to CMAKE_PREFIX_PATH") LIST(APPEND CMAKE_PREFIX_PATH "/opt/wavelab") ENDIF() -# Require Eigen 3.2.92, also called 3.3 beta-1, since it's in xenial FIND_PACKAGE(Eigen3 3.2.92 REQUIRED) FIND_PACKAGE(Boost 1.54.0 COMPONENTS system filesystem) FIND_PACKAGE(PCL 1.8 COMPONENTS @@ -52,6 +51,7 @@ FIND_PACKAGE(OpenCV 3.2.0) FIND_PACKAGE(yaml-cpp REQUIRED) FIND_PACKAGE(Ceres 1.12) FIND_PACKAGE(GTSAM) +#set(CMAKE_MODULE_PATH "${CMAKE_MODULE_PATH};/usr/share/cmake/geographiclib") FIND_PACKAGE(GeographicLib 1.49) # Where dependencies do not provide IMPORTED targets, define them @@ -59,7 +59,6 @@ INCLUDE(cmake/ImportEigen3.cmake) INCLUDE(cmake/ImportBoost.cmake) INCLUDE(cmake/ImportPCL.cmake) INCLUDE(cmake/ImportKindr.cmake) -INCLUDE(cmake/ImportYaml-cpp.cmake) INCLUDE(cmake/ImportCeres.cmake) # Optionally build tests. `gtest` is included with this project diff --git a/README.md b/README.md index 27f55f62..6a1bff0a 100644 --- a/README.md +++ b/README.md @@ -41,14 +41,15 @@ Some earlier versions may work, but are not tested. - gtsam - GeographicLib 1.49 -Building libwave requires CMake 3.2 and a C++11 compiler (tested on GCC 5.4). +Building libwave requires CMake 3.16 and a C++17 compiler (tested on GCC 5.4). ### Installing dependencies The basic set of dependencies can be installed with the Ubuntu package manager using the command - sudo apt-get install libboost-dev libyaml-cpp-dev libeigen3-dev \ - build-essential cmake +``` +# apt-get install libboost-dev libyaml-cpp-dev libeigen3-dev build-essential cmake +``` For convenience, scripts to install other dependencies on Ubuntu 16.04 are provided in `scripts/install`. **Note**: the scripts are not tested on a wide @@ -69,16 +70,16 @@ described above. Then build using CMake: cd build cmake .. make -j8 - + By default, all libraries whose dependencies are found will be built. Individual libraries can be disabled using CMake options. For example, cmake .. -DBUILD_wave_vision=OFF - + will disable building `wave_vision`. Install libwave by running `make install`. Alternatively, you can enable the -`EXPORT_BUILD` option in CMake, which will make the libwave build directory +`EXPORT_BUILD` option in CMake, which will make the libwave build directory searchable by CMake without installation. @@ -94,7 +95,7 @@ installed elsewhere). A workaround is to remove OpenCV 2 via One libwave has been either installed or exported by CMake, it can be used in your project's `CMakeLists.txt` file as follows: - cmake_minimum_required(VERSION 3.0) + cmake_minimum_required(VERSION 3.16) project(example) find_package(wave REQUIRED geometry matching) diff --git a/cmake/ImportYaml-cpp.cmake b/cmake/ImportYaml-cpp.cmake deleted file mode 100644 index 72853744..00000000 --- a/cmake/ImportYaml-cpp.cmake +++ /dev/null @@ -1,10 +0,0 @@ -# - Fixes imported target for yaml-cpp -# For some reason yaml-cpp does not have include directories in its imported -# target. Add them to the target, if not already set. -IF(TARGET yaml-cpp) - GET_TARGET_PROPERTY(current_property yaml-cpp INTERFACE_INCLUDE_DIRECTORIES) - IF(NOT current_property) - SET_TARGET_PROPERTIES(yaml-cpp PROPERTIES INTERFACE_INCLUDE_DIRECTORIES - "${YAML_CPP_INCLUDE_DIR}") - ENDIF() -ENDIF() diff --git a/cmake/waveConfig.cmake.in b/cmake/waveConfig.cmake.in index 1b03af83..b0836886 100644 --- a/cmake/waveConfig.cmake.in +++ b/cmake/waveConfig.cmake.in @@ -102,7 +102,6 @@ INCLUDE(${WAVE_EXTRA_CMAKE_DIR}/ImportEigen3.cmake) INCLUDE(${WAVE_EXTRA_CMAKE_DIR}/ImportBoost.cmake) INCLUDE(${WAVE_EXTRA_CMAKE_DIR}/ImportPCL.cmake) INCLUDE(${WAVE_EXTRA_CMAKE_DIR}/ImportKindr.cmake) -INCLUDE(${WAVE_EXTRA_CMAKE_DIR}/ImportYaml-cpp.cmake) INCLUDE(${WAVE_EXTRA_CMAKE_DIR}/ImportCeres.cmake) # This file contains definitions of IMPORTED targets diff --git a/deps/googletest b/deps/googletest index aa148eb2..3b49be07 160000 --- a/deps/googletest +++ b/deps/googletest @@ -1 +1 @@ -Subproject commit aa148eb2b7f70ede0eb10de34b6254826bfb34f4 +Subproject commit 3b49be074d5c1340eeb447e6a8e78427051e675a diff --git a/package.xml b/package.xml index 1cf954aa..8c7676f7 100644 --- a/package.xml +++ b/package.xml @@ -1,14 +1,21 @@ - + + libwave - 0.1.0 + 0.1.1 libwave - Chris Choi - Leo Koppel + Chris Choi + Leo Koppel + Michal Antkiewicz MIT catkin + boost + eigen + geographiclib + yaml-cpp + rosunit cmake diff --git a/scripts/plot/quadrotor_plot.py b/scripts/plot/quadrotor_plot.py index 3f6fb421..a544b4d0 100755 --- a/scripts/plot/quadrotor_plot.py +++ b/scripts/plot/quadrotor_plot.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python2 +#!/usr/bin/env python3 import csv import matplotlib.pylab as plt diff --git a/wave_containers/CMakeLists.txt b/wave_containers/CMakeLists.txt index 22fe1ae6..e0e1ff70 100644 --- a/wave_containers/CMakeLists.txt +++ b/wave_containers/CMakeLists.txt @@ -3,7 +3,8 @@ PROJECT(wave_containers) WAVE_ADD_MODULE(${PROJECT_NAME} DEPENDS Eigen3::Eigen - Boost::boost) + Boost::boost + wave::utils) # Unit tests IF(BUILD_TESTING) diff --git a/wave_controls/CMakeLists.txt b/wave_controls/CMakeLists.txt index f49fb525..135fd37b 100644 --- a/wave_controls/CMakeLists.txt +++ b/wave_controls/CMakeLists.txt @@ -3,6 +3,7 @@ PROJECT(wave_controls) WAVE_ADD_MODULE(${PROJECT_NAME} DEPENDS Eigen3::Eigen + wave::utils SOURCES src/pid.cpp) diff --git a/wave_geometry b/wave_geometry index 27be85b3..aabcad44 160000 --- a/wave_geometry +++ b/wave_geometry @@ -1 +1 @@ -Subproject commit 27be85b37f25b8bb7ec4cd3fc189d3fc9fb7361d +Subproject commit aabcad44a490fc6393b35e63db9ad8908cf46dec diff --git a/wave_gtsam/tests/gtsam/gtsam_offline_example.cpp b/wave_gtsam/tests/gtsam/gtsam_offline_example.cpp index efa1e6cf..36b82cc1 100644 --- a/wave_gtsam/tests/gtsam/gtsam_offline_example.cpp +++ b/wave_gtsam/tests/gtsam/gtsam_offline_example.cpp @@ -6,6 +6,7 @@ #include #include #include +#include #include "wave/wave_test.hpp" #include "wave/vision/dataset/VoDataset.hpp" diff --git a/wave_gtsam/tests/gtsam/gtsam_offline_kitti_example.cpp b/wave_gtsam/tests/gtsam/gtsam_offline_kitti_example.cpp index 19e923f1..c283b19c 100644 --- a/wave_gtsam/tests/gtsam/gtsam_offline_kitti_example.cpp +++ b/wave_gtsam/tests/gtsam/gtsam_offline_kitti_example.cpp @@ -6,6 +6,7 @@ #include #include #include +#include #include "wave/wave_test.hpp" #include "wave/vision/dataset/VoDataset.hpp" diff --git a/wave_matching/include/wave/matching/impl/ground_segmentation.hpp b/wave_matching/include/wave/matching/impl/ground_segmentation.hpp index fed34b47..20d685e9 100644 --- a/wave_matching/include/wave/matching/impl/ground_segmentation.hpp +++ b/wave_matching/include/wave/matching/impl/ground_segmentation.hpp @@ -227,7 +227,7 @@ void GroundSegmentation::sectorINSAC(int sector_index) { if (Vf_s.rows() == 0) { keep_going = false; - LOG_INFO("WARNING BREAKING LOOP: VF_s does not exist"); + LOG_INFO("Ground segmentation: BREAKING LOOP: VF_s does not exist"); continue; } diff --git a/wave_vision/include/wave/vision/detector/fast_detector.hpp b/wave_vision/include/wave/vision/detector/fast_detector.hpp index b6a6efeb..c5f9da88 100644 --- a/wave_vision/include/wave/vision/detector/fast_detector.hpp +++ b/wave_vision/include/wave/vision/detector/fast_detector.hpp @@ -22,7 +22,7 @@ struct FASTDetectorParams { FASTDetectorParams(const int threshold, const bool nonmax_suppression, - const int type, + const cv::FastFeatureDetector::DetectorType type, const int num_features) : threshold(threshold), nonmax_suppression(nonmax_suppression), @@ -54,11 +54,11 @@ struct FASTDetectorParams { * deem the point as a corner. * * Options: - * cv::FastFeatureDetector::TYPE_5_8 - * cv::FastFeatureDetector::TYPE_7_12 - * cv::FastFeatureDetector::TYPE_9_16 (recommended) + * ccv::FastFeatureDetector::DetectorType::TYPE_5_8 + * ccv::FastFeatureDetector::DetectorType::TYPE_7_12 + * ccv::FastFeatureDetector::DetectorType::TYPE_9_16 (recommended) */ - int type = cv::FastFeatureDetector::TYPE_9_16; + cv::FastFeatureDetector::DetectorType type = cv::FastFeatureDetector::DetectorType::TYPE_9_16; /** The number of features to keep from detection. * diff --git a/wave_vision/include/wave/vision/detector/orb_detector.hpp b/wave_vision/include/wave/vision/detector/orb_detector.hpp index d6529890..37ec3ca6 100644 --- a/wave_vision/include/wave/vision/detector/orb_detector.hpp +++ b/wave_vision/include/wave/vision/detector/orb_detector.hpp @@ -33,7 +33,7 @@ struct ORBDetectorParams { const float scale_factor, const int num_levels, const int edge_threshold, - const int score_type, + const cv::ORB::ScoreType score_type, const int fast_threshold) : num_features(num_features), scale_factor(scale_factor), @@ -82,11 +82,11 @@ struct ORBDetectorParams { * alternative option. cv::ORB::FAST_SCORE is slightly faster than * cv::ORB::HARRIS_SCORE, but the results are not as stable. * - * Options: cv::ORB::HARRIS_SCORE, cv::ORB::FAST_SCORE + * Options: cv::ORB::ScoreType::HARRIS_SCORE, cv::ORB::ScoreType::FAST_SCORE * - * Default: cv::ORB::HARRIS_SCORE + * Default: cv::ORB::ScoreType::HARRIS_SCORE */ - int score_type = cv::ORB::HARRIS_SCORE; + cv::ORB::ScoreType score_type = cv::ORB::ScoreType::HARRIS_SCORE; /** Threshold on difference between intensity of the central pixel, and * pixels in a circle (Bresenham radius 3) around this pixel. diff --git a/wave_vision/src/descriptor/orb_descriptor.cpp b/wave_vision/src/descriptor/orb_descriptor.cpp index 112e741b..d907de9c 100644 --- a/wave_vision/src/descriptor/orb_descriptor.cpp +++ b/wave_vision/src/descriptor/orb_descriptor.cpp @@ -37,7 +37,7 @@ ORBDescriptor::ORBDescriptor(const ORBDescriptorParams &config) { int num_levels = 8; int edge_threshold = 31; int first_level = 0; // As per OpenCV docs, first_level must be zero. - int score_type = cv::ORB::HARRIS_SCORE; + cv::ORB::ScoreType score_type = cv::ORB::ScoreType::HARRIS_SCORE; int fast_threshold = 20; // Create cv::ORB object with the desired parameters diff --git a/wave_vision/src/detector/fast_detector.cpp b/wave_vision/src/detector/fast_detector.cpp index 1a3ae8e4..9ad8a889 100644 --- a/wave_vision/src/detector/fast_detector.cpp +++ b/wave_vision/src/detector/fast_detector.cpp @@ -26,7 +26,13 @@ FASTDetectorParams::FASTDetectorParams(const std::string &config_path) { this->threshold = threshold; this->nonmax_suppression = nonmax_suppression; - this->type = type; + if (type == 0) { + this->type = cv::FastFeatureDetector::DetectorType::TYPE_5_8; + } else if (type == 1) { + this->type = cv::FastFeatureDetector::DetectorType::TYPE_7_12; + } else if (type == 2) { + this->type = cv::FastFeatureDetector::DetectorType::TYPE_9_16; + } this->num_features = num_features; } diff --git a/wave_vision/src/detector/orb_detector.cpp b/wave_vision/src/detector/orb_detector.cpp index 656e9cd2..68fce493 100644 --- a/wave_vision/src/detector/orb_detector.cpp +++ b/wave_vision/src/detector/orb_detector.cpp @@ -32,7 +32,11 @@ ORBDetectorParams::ORBDetectorParams(const std::string &config_path) { this->scale_factor = scale_factor; this->num_levels = num_levels; this->edge_threshold = edge_threshold; - this->score_type = score_type; + if (score_type == 0) { + this->score_type = cv::ORB::ScoreType::HARRIS_SCORE; + } else if (score_type == 1) { + this->score_type = cv::ORB::ScoreType::FAST_SCORE; + } this->fast_threshold = fast_threshold; } diff --git a/wave_vision/tests/detector_tests/fast_tests.cpp b/wave_vision/tests/detector_tests/fast_tests.cpp index 849f3211..e629dd46 100644 --- a/wave_vision/tests/detector_tests/fast_tests.cpp +++ b/wave_vision/tests/detector_tests/fast_tests.cpp @@ -13,7 +13,7 @@ TEST(FASTTests, GoodConfig) { // Custom params struct (with good values) int threshold = 10; bool nms = true; - int type = cv::FastFeatureDetector::TYPE_9_16; + cv::FastFeatureDetector::DetectorType type = cv::FastFeatureDetector::DetectorType::TYPE_9_16; int num_features = 10; EXPECT_NO_THROW( @@ -46,16 +46,6 @@ TEST(FASTTests, BadThresholdConfiguration) { ASSERT_THROW(FASTDetector bad_threshold(config), std::invalid_argument); } -TEST(FASTTests, BadTypeConfiguration) { - FASTDetectorParams config; - config.type = -1; - - ASSERT_THROW(FASTDetector bad_type1(config), std::invalid_argument); - - config.type = 4; - ASSERT_THROW(FASTDetector bad_type2(config), std::invalid_argument); -} - TEST(FASTTests, BadNumFeatures) { FASTDetectorParams config; config.num_features = -1; @@ -97,10 +87,6 @@ TEST(FASTTests, BadNewConfiguration) { ASSERT_THROW(detector.configure(new_config), std::invalid_argument); - FASTDetectorParams new_config_2; - new_config_2.type = -1; - ASSERT_THROW(detector.configure(new_config_2), std::invalid_argument); - FASTDetectorParams new_config_3; new_config_3.num_features = -5; ASSERT_THROW(detector.configure(new_config_3), std::invalid_argument); diff --git a/wave_vision/tests/detector_tests/orb_tests.cpp b/wave_vision/tests/detector_tests/orb_tests.cpp index 5ba55380..594b498b 100644 --- a/wave_vision/tests/detector_tests/orb_tests.cpp +++ b/wave_vision/tests/detector_tests/orb_tests.cpp @@ -15,7 +15,7 @@ TEST(ORBDetectorTests, GoodConfig) { float scale_factor = 1.2f; int num_levels = 8; int edge_threshold = 31; - int score_type = cv::ORB::HARRIS_SCORE; + cv::ORB::ScoreType score_type = cv::ORB::HARRIS_SCORE; int fast_threshold = 20; EXPECT_NO_THROW(ORBDetectorParams config2(num_features, @@ -79,17 +79,6 @@ TEST(ORBDetectorTests, BadEdgeThreshold) { ASSERT_THROW(ORBDetector bad_edgethreshold(config), std::invalid_argument); } -TEST(ORBDetectorTests, BadScoreType) { - ORBDetectorParams config; - - config.score_type = -1; - - ASSERT_THROW(ORBDetector bad_scoretype1(config), std::invalid_argument); - - config.score_type = 2; - ASSERT_THROW(ORBDetector bad_scoretype2(config), std::invalid_argument); -} - TEST(ORBDetectorTests, BadFastThreshold) { ORBDetectorParams config; config.fast_threshold = 0; @@ -147,10 +136,6 @@ TEST(ORBDetectorTests, BadNewConfiguration) { config4.edge_threshold = -1; ASSERT_THROW(detector.configure(config4), std::invalid_argument); - ORBDetectorParams config5; - config5.score_type = -1; - ASSERT_THROW(detector.configure(config5), std::invalid_argument); - ORBDetectorParams config6; config6.fast_threshold = -1; ASSERT_THROW(detector.configure(config6), std::invalid_argument);