Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
27 commits
Select commit Hold shift + click to select a range
7632012
update wave_geometry(master), change libwave to CXX 17
mantkiew Dec 7, 2020
f59db43
update README, add rosdep deps to package.xml
mantkiew Dec 7, 2020
9077ec8
update googletest(master)
mantkiew Dec 7, 2020
05a6253
switch googletest from master (rolling release) to 1.10
mantkiew Dec 7, 2020
1709de4
add geographiclib to rosdeps
mantkiew Dec 7, 2020
d1824f7
add rosunit as <test_depend> in package.xml
mantkiew Dec 8, 2020
3d8653d
Log debug ground segmentation (#296)
mantkiew Jun 30, 2021
5077e7b
Merge branch 'master' into update_wave_geometry_master_cpp_17
mantkiew Jun 30, 2021
83f4928
explicitly include gtsam/geometry/SimpleCamera.h to work with gtsam 4…
mantkiew Sep 27, 2021
6e68d26
update with master, resolve merge conflict
mantkiew Sep 27, 2021
0d64989
update wave_geometry(master)
mantkiew Sep 27, 2021
d112a5e
use LOG_INFO
mantkiew Sep 27, 2021
199543d
fix gtsam_offline_kitti_example test: include SimpleCamera explicitly
mantkiew Sep 27, 2021
44df50d
update googletest(master)
mantkiew Oct 1, 2021
c3c4e0a
upgrade OpenCV to 4.2
mantkiew Oct 1, 2021
c8460c9
remove ImportYaml-cpp.cmake which causes a build error and which is n…
mantkiew Oct 1, 2021
0083f59
use cv::FastFeatureDetector::DetectorType and remove redundant tests
mantkiew Oct 1, 2021
9baa10d
use cv::ORB::ScoreType and remove redundant tests
mantkiew Oct 1, 2021
c788877
switch to python3
mantkiew Oct 4, 2021
b23ad2f
switch to format 3, prepare for ROS2, adjust authors/maintainers
mantkiew Dec 7, 2022
9ee457e
update lib versions for focal/noetic
mantkiew Apr 17, 2023
d324bf1
update wave_geometry(focal_noetic)
mantkiew Apr 17, 2023
4a5f58d
fix finding GeographicLib to work with the default installation
mantkiew May 11, 2023
3046d14
use correct PCL verion on focal: 1.10
mantkiew May 11, 2023
a2a7619
cmake 3.16
mantkiew Apr 24, 2024
4690b40
update wave_geometry(master): no need for focal_noetic branch
mantkiew Apr 24, 2024
dad6ef7
revert version numbers to the ones from master, restore build type cmake
mantkiew Apr 25, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 4 additions & 5 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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 <version>)
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)

Expand Down Expand Up @@ -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
Expand All @@ -52,14 +51,14 @@ 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
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
Expand Down
15 changes: 8 additions & 7 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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.


Expand All @@ -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)
Expand Down
10 changes: 0 additions & 10 deletions cmake/ImportYaml-cpp.cmake

This file was deleted.

1 change: 0 additions & 1 deletion cmake/waveConfig.cmake.in
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion deps/googletest
Submodule googletest updated 395 files
15 changes: 11 additions & 4 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,14 +1,21 @@
<package format="2">
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>libwave</name>
<version>0.1.0</version>
<version>0.1.1</version>
<description>libwave</description>

<maintainer email="chutsu@gmail.com">Chris Choi</maintainer>
<maintainer email="lkoppel@uwaterloo.ca">Leo Koppel</maintainer>
<author email="chutsu@gmail.com">Chris Choi</author>
<author email="lkoppel@uwaterloo.ca">Leo Koppel</author>
<maintainer email="michal.antkiewicz@uwaterloo.ca">Michal Antkiewicz</maintainer>
<license>MIT</license>

<!-- This file lets catkin build this non-catkin package-->
<buildtool_depend>catkin</buildtool_depend>
<depend>boost</depend>
<depend>eigen</depend>
<depend>geographiclib</depend>
<depend>yaml-cpp</depend>
<test_depend>rosunit</test_depend>
<export>
<build_type>cmake</build_type>
</export>
Expand Down
2 changes: 1 addition & 1 deletion scripts/plot/quadrotor_plot.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#!/usr/bin/env python2
#!/usr/bin/env python3
import csv
import matplotlib.pylab as plt

Expand Down
3 changes: 2 additions & 1 deletion wave_containers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
1 change: 1 addition & 0 deletions wave_controls/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@ PROJECT(wave_controls)
WAVE_ADD_MODULE(${PROJECT_NAME}
DEPENDS
Eigen3::Eigen
wave::utils
SOURCES
src/pid.cpp)

Expand Down
2 changes: 1 addition & 1 deletion wave_geometry
Submodule wave_geometry updated 162 files
1 change: 1 addition & 0 deletions wave_gtsam/tests/gtsam/gtsam_offline_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/inference/Symbol.h>
#include <gtsam/linear/Sampler.h>
#include <gtsam/geometry/SimpleCamera.h>

#include "wave/wave_test.hpp"
#include "wave/vision/dataset/VoDataset.hpp"
Expand Down
1 change: 1 addition & 0 deletions wave_gtsam/tests/gtsam/gtsam_offline_kitti_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/inference/Symbol.h>
#include <gtsam/linear/Sampler.h>
#include <gtsam/geometry/SimpleCamera.h>

#include "wave/wave_test.hpp"
#include "wave/vision/dataset/VoDataset.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -227,7 +227,7 @@ void GroundSegmentation<PointT>::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;
}

Expand Down
10 changes: 5 additions & 5 deletions wave_vision/include/wave/vision/detector/fast_detector.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down Expand Up @@ -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.
*
Expand Down
8 changes: 4 additions & 4 deletions wave_vision/include/wave/vision/detector/orb_detector.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down Expand Up @@ -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.
Expand Down
2 changes: 1 addition & 1 deletion wave_vision/src/descriptor/orb_descriptor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
8 changes: 7 additions & 1 deletion wave_vision/src/detector/fast_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}

Expand Down
6 changes: 5 additions & 1 deletion wave_vision/src/detector/orb_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}

Expand Down
16 changes: 1 addition & 15 deletions wave_vision/tests/detector_tests/fast_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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);
Expand Down
17 changes: 1 addition & 16 deletions wave_vision/tests/detector_tests/orb_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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);
Expand Down