From 2d0349cc36ae10fbb6c9c74454c63b381bb11d8f Mon Sep 17 00:00:00 2001 From: Vincenzo Polizzi Date: Mon, 18 Apr 2022 21:14:33 +0200 Subject: [PATCH 1/8] x library as standalone --- .gitignore | 1 + CMakeLists.txt | 136 +++++++++++++++++++++++++++++--------------- src/x/ekf/ekf.cpp | 4 +- x.pc.in | 11 ++++ xConfig.cmake.in | 60 +++++++++++++++++++ xUninstall.cmake.in | 28 +++++++++ 6 files changed, 191 insertions(+), 49 deletions(-) create mode 100644 x.pc.in create mode 100644 xConfig.cmake.in create mode 100644 xUninstall.cmake.in diff --git a/.gitignore b/.gitignore index 70bb441..dae7ac4 100644 --- a/.gitignore +++ b/.gitignore @@ -1,3 +1,4 @@ +build # Temporary/backup files *~ *.sw* diff --git a/CMakeLists.txt b/CMakeLists.txt index a21d662..4cf2635 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,44 +1,49 @@ +cmake_minimum_required(VERSION 3.16) +project(x VERSION 1.1.0) + +if (NOT CMAKE_BUILD_TYPE) + set(CMAKE_BUILD_TYPE "Release" CACHE STRING "" FORCE) +endif() + ################################################################################# # User build settings -set(DUAL_THREAD true) # Set true to process image and inertial data on different +OPTION(MULTI_THREAD "Multi thread" ON) # Set true to process image and inertial data on different # threads -set(VERBOSE true) # Set false to disable all publishing and standard output + +option(VERBOSE "Publish std out and other data" ON) # Set false to disable all publishing and standard output # stream, except pose at update rate. That will improve runtime. -set(TIMING false) # Set true to enable timers -set(PROFILING false) # Set true to disable compiler flags which are not + +option(TIMING "Publish std out and other data" OFF) # Set true to enable timers + +option(PROFILING "Publish std out and other data" OFF) # Set true to disable compiler flags which are not # compatible with Callgrind profiling tool. -set(UNIT_TESTS false) # Set true to enable unit tests + +option(UNIT_TESTS "Publish std out and other data" OFF) # Set true to enable unit tests ################################################################################# -cmake_minimum_required(VERSION 2.8.3) -project(x) -set (CMAKE_BUILD_TYPE Release) +# set (CMAKE_BUILD_TYPE Release) # Set definitions -if(DUAL_THREAD) - add_definitions(-DDUAL_THREAD) +if(MULTI_THREAD) + message("Multi-thread: ON") + add_definitions(-DMULTI_THREAD) endif() if(VERBOSE) + message("Verbose: ON") add_definitions(-DVERBOSE) endif() if(TIMING) + message("Timing: ON") add_definitions(-DTIMING) endif() if(UNIT_TESTS) + message("Unit Tests: ON") add_definitions(-DRUN_UNIT_TESTS) endif() -if (CMAKE_BUILD_TYPE MATCHES Debug) - add_definitions(-DDEBUG -DDEBUGMSF) -elseif (CMAKE_BUILD_TYPE MATCHES RelWithDebInfo) - # Enable asserts - add_definitions(-UNDEBUG) -endif() -add_definitions(-D_LINUX -D_REENTRANT) -# Eigen plugin -add_definitions(-DEIGEN_MATRIXBASE_PLUGIN=) +add_definitions(-D_LINUX -D_REENTRANT) # Look for OpenCV >= 3.3.1 find_package(OpenCV 4 QUIET) @@ -49,21 +54,15 @@ if(NOT ${OpenCV_FOUND}) endif() endif() -find_package(catkin REQUIRED COMPONENTS - cmake_modules -) - +# Eigen plugin +add_definitions(-DEIGEN_MATRIXBASE_PLUGIN=) find_package(Eigen3 REQUIRED) # Set build flags, depending on the architecture -set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -Wall") - -if (CMAKE_BUILD_TYPE MATCHES Debug) - set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -g -O0") -endif() +set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14 -Wall") if (CMAKE_BUILD_TYPE MATCHES Release) - + message("Release Mode") set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O3") if(CMAKE_SYSTEM_PROCESSOR STREQUAL "aarch64") # tested on Jetson TX2 @@ -75,30 +74,25 @@ if (CMAKE_BUILD_TYPE MATCHES Release) if (${PROFILING} MATCHES false) set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -funsafe-loop-optimizations -fsee -funroll-loops -fno-math-errno -funsafe-math-optimizations -ffinite-math-only -fno-signed-zeros") endif() - + +elseif (CMAKE_BUILD_TYPE MATCHES Debug) + message("Debug Mode") + add_definitions(-DDEBUG -DDEBUGMSF) + set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -g -O0") +elseif (CMAKE_BUILD_TYPE MATCHES RelWithDebInfo) + message("Release with Debug Info Mode") + # Enable asserts + add_definitions(-UNDEBUG) endif() -# For downstream packages in catkin set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR}) set(EIGEN3_LIBRARIES ${EIGEN3_LIBRARIES}) -# Configure this package -catkin_package( - DEPENDS EIGEN3 - INCLUDE_DIRS include ${EIGEN3_INCLUDE_DIR} - LIBRARIES x -) - -## Package internal and additional locations of header files -## Separating the projects include directory from {catkin_INCLUDE_DIRS} -## allows to tag that with SYSTEM, which disables GCC warnings for -## these (all the ros header, opencv, ..) include_directories (include) include_directories (SYSTEM ${OpenCV_INCLUDE_DIRS} - ${catkin_INCLUDE_DIRS} - ${EIGEN3_INCLUDE_DIR} + ${EIGEN3_INCLUDE_DIRS} ) set (SOURCE @@ -122,13 +116,61 @@ set (SOURCE src/x/vision/timing.cpp src/x/vision/tracker.cpp src/x/vision/triangulation.cpp - ) -add_library (x ${SOURCE}) +add_library(x ${SOURCE}) # Additional libraries to link against target_link_libraries(x ${OpenCV_LIBRARIES} - ${catkin_LIBRARIES} + ${EIGEN3_LIBRARIES} ) + +# Uninstall Target +configure_file("${CMAKE_CURRENT_SOURCE_DIR}/xUninstall.cmake.in" "${CMAKE_CURRENT_BINARY_DIR}/xUninstall.cmake" IMMEDIATE @ONLY) +add_custom_target(uninstall "${CMAKE_COMMAND}" -P "${CMAKE_CURRENT_BINARY_DIR}/xUninstall.cmake") + +set(CMAKE_INSTALL_LIBDIR lib) + +# Generate pkg-config file +configure_file(${CMAKE_CURRENT_SOURCE_DIR}/${PROJECT_NAME}.pc.in ${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}.pc @ONLY) + +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}.pc DESTINATION ${CMAKE_INSTALL_LIBDIR}/pkgconfig) + +# Cmake find_package() support. +set(CMAKE_EXPORT_DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/${PROJECT_NAME}) +include(CMakePackageConfigHelpers) + +install(TARGETS x EXPORT xTargets) +install(EXPORT xTargets + DESTINATION ${CMAKE_EXPORT_DESTINATION} +) +install(DIRECTORY include/ DESTINATION include) +configure_package_config_file(xConfig.cmake.in + ${CMAKE_CURRENT_BINARY_DIR}/xConfig.cmake + INSTALL_DESTINATION ${CMAKE_EXPORT_DESTINATION} +) +write_basic_package_version_file(${CMAKE_CURRENT_BINARY_DIR}/xConfigVersion.cmake + COMPATIBILITY SameMajorVersion +) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/xConfig.cmake + ${CMAKE_CURRENT_BINARY_DIR}/xConfigVersion.cmake + DESTINATION ${CMAKE_EXPORT_DESTINATION} +) + +# Support automatic RPM/DEB generation via CPack +SET(CPACK_CMAKE_GENERATOR ${CMAKE_GENERATOR}) +set(CPACK_PACKAGE_NAME ${PROJECT_NAME}) +set(CPACK_PACKAGE_VERSION ${PROJECT_VERSION}) +set(CPACK_PACKAGE_RELEASE 1) +set(CPACK_PACKAGE_CONTACT "polivicio@gmail.com") +set(CPACK_PACKAGE_VENDOR "JPL") +set(CPACK_PACKAGE_DESCRIPTION "Generic C++ library for vision-based navigation, with multi-sensor fusion capabilities for thermal, range, solar and GPS measurements.") +set(CPACK_PACKAGE_DESCRIPTION_SUMMARY ${CPACK_PACKAGE_DESCRIPTION}) +set(CPACK_PACKAGING_INSTALL_PREFIX ${CMAKE_INSTALL_PREFIX}) +set(CPACK_PACKAGE_FILE_NAME "${CPACK_PACKAGE_NAME}.${CMAKE_SYSTEM_PROCESSOR}") +set(CPACK_GENERATOR "RPM" "DEB") +set(CPACK_RPM_PACKAGE_AUTOREQ 1) +set(CPACK_DEBIAN_PACKAGE_SHLIBDEPS 1) + +include(CPack) diff --git a/src/x/ekf/ekf.cpp b/src/x/ekf/ekf.cpp index 4860f30..b692e77 100644 --- a/src/x/ekf/ekf.cpp +++ b/src/x/ekf/ekf.cpp @@ -178,13 +178,13 @@ State Ekf::processUpdateMeasurement() { } void Ekf::lock() { -#ifdef DUAL_THREAD +#ifdef MULTI_THREAD mutex_.lock(); #endif } void Ekf::unlock() { -#ifdef DUAL_THREAD +#ifdef MULTI_THREAD mutex_.unlock(); #endif } diff --git a/x.pc.in b/x.pc.in new file mode 100644 index 0000000..58e77aa --- /dev/null +++ b/x.pc.in @@ -0,0 +1,11 @@ +prefix=@CMAKE_INSTALL_PREFIX@ +exec_prefix=${prefix} +libdir=${prefix}/@CMAKE_INSTALL_LIBDIR@ +includedir=${prefix}/@CMAKE_INSTALL_INCLUDEDIR@ + +Name: @PROJECT_NAME@ +Description: Generic C++ library for vision-based navigation, with multi-sensor fusion capabilities for thermal, range, solar and GPS measurements. +Version: @PROJECT_VERSION@ +Requires: opencv2 >= 3.3.1, libzstd +Libs: @SYSTEM_THREAD_LIBS@ +Cflags: -I${includedir} diff --git a/xConfig.cmake.in b/xConfig.cmake.in new file mode 100644 index 0000000..77942cc --- /dev/null +++ b/xConfig.cmake.in @@ -0,0 +1,60 @@ +# =================================================================================== +# @PROJECT_NAME@ CMake configuration file +# +# ** File generated automatically, do not modify ** +# +# Usage from an external project: +# In your CMakeLists.txt, add these lines: +# +# FIND_PACKAGE(@PROJECT_NAME@ REQUIRED ) +# TARGET_LINK_LIBRARIES(MY_TARGET_NAME ${@PROJECT_NAME@_LIBS}) +# +# This file will define the following variables: +# - @PROJECT_NAME@_LIBS : The list of libraries to links against. +# - @PROJECT_NAME@_LIB_DIR : The directory where lib files are. Calling LINK_DIRECTORIES +# with this path is NOT needed. +# - @PROJECT_NAME@_VERSION : The version of this PROJECT_NAME build. Example: "1.2.0" +# - @PROJECT_NAME@_VERSION_MAJOR : Major version part of VERSION. Example: "1" +# - @PROJECT_NAME@_VERSION_MINOR : Minor version part of VERSION. Example: "2" +# - @PROJECT_NAME@_VERSION_PATCH : Patch version part of VERSION. Example: "0" +# +# =================================================================================== + +# Look for OpenCV >= 3.3.1 +find_package(OpenCV 4 QUIET) +if(NOT ${OpenCV_FOUND}) + find_package(OpenCV 3.3.1 QUIET) + if(NOT ${OpenCV_FOUND}) + message(FATAL_ERROR "OpenCV >= 3.3.1 required.") + endif() +endif() + +# Eigen plugin +add_definitions(-DEIGEN_MATRIXBASE_PLUGIN=) + +find_package(Eigen3 REQUIRED) +if(NOT ${Eigen3_FOUND}) + message(FATAL_ERROR "Eigen3 required.") +endif() + +@PACKAGE_INIT@ + +include_directories("@CMAKE_INSTALL_PREFIX@/include" + ${OpenCV_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS}) +set(@PROJECT_NAME@_INCLUDE_DIRS "@CMAKE_INSTALL_PREFIX@/include" + ${OpenCV_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS}) +check_required_components(x) + +LINK_DIRECTORIES("@CMAKE_INSTALL_PREFIX@/lib") +set(@PROJECT_NAME@_LIB_DIR "@CMAKE_INSTALL_PREFIX@/lib") + +set(@PROJECT_NAME@_LIBS @REQUIRED_LIBRARIES@ @PROJECT_NAME@@PROJECT_DLLVERSION@) + +set(@PROJECT_NAME@_FOUND YES) +set(@PROJECT_NAME@_FOUND "YES") +set(@PROJECT_NAME@_VERSION @PROJECT_VERSION@) +set(@PROJECT_NAME@_VERSION_MAJOR @PROJECT_VERSION_MAJOR@) +set(@PROJECT_NAME@_VERSION_MINOR @PROJECT_VERSION_MINOR@) +set(@PROJECT_NAME@_VERSION_PATCH @PROJECT_VERSION_PATCH@) diff --git a/xUninstall.cmake.in b/xUninstall.cmake.in new file mode 100644 index 0000000..58a628f --- /dev/null +++ b/xUninstall.cmake.in @@ -0,0 +1,28 @@ +# ----------------------------------------------- +# File that provides "make uninstall" target +# We use the file 'install_manifest.txt' +# ----------------------------------------------- +IF(NOT EXISTS "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt") + MESSAGE(FATAL_ERROR "Cannot find install manifest: \"@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt\"") +ENDIF(NOT EXISTS "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt") + +FILE(READ "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt" files) +STRING(REGEX REPLACE "\n" ";" files "${files}") +FOREACH(file ${files}) + MESSAGE(STATUS "Uninstalling \"$ENV{DESTDIR}${file}\"") + IF(EXISTS "$ENV{DESTDIR}${file}") + EXEC_PROGRAM( + "@CMAKE_COMMAND@" ARGS "-E remove \"$ENV{DESTDIR}${file}\"" + OUTPUT_VARIABLE rm_out + RETURN_VALUE rm_retval + ) + EXECUTE_PROCESS(COMMAND rm -rf $ENV{DESTDIR}${file}) + IF(NOT "${rm_retval}" STREQUAL 0) + MESSAGE(FATAL_ERROR "Problem when removing \"$ENV{DESTDIR}${file}\"") + ENDIF(NOT "${rm_retval}" STREQUAL 0) + ELSE(EXISTS "$ENV{DESTDIR}${file}") + MESSAGE(STATUS "File \"$ENV{DESTDIR}${file}\" does not exist.") + ENDIF(EXISTS "$ENV{DESTDIR}${file}") +ENDFOREACH(file) + + From e607f5d79b704da406fae2e44691d110ebffbf88 Mon Sep 17 00:00:00 2001 From: Vincenzo Polizzi Date: Mon, 18 Apr 2022 21:31:33 +0200 Subject: [PATCH 2/8] Removed catkin package dependencies. --- CMakeLists.txt | 4 ++-- package.xml | 14 -------------- 2 files changed, 2 insertions(+), 16 deletions(-) delete mode 100644 package.xml diff --git a/CMakeLists.txt b/CMakeLists.txt index 4cf2635..0bc2898 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -163,8 +163,8 @@ SET(CPACK_CMAKE_GENERATOR ${CMAKE_GENERATOR}) set(CPACK_PACKAGE_NAME ${PROJECT_NAME}) set(CPACK_PACKAGE_VERSION ${PROJECT_VERSION}) set(CPACK_PACKAGE_RELEASE 1) -set(CPACK_PACKAGE_CONTACT "polivicio@gmail.com") -set(CPACK_PACKAGE_VENDOR "JPL") +set(CPACK_PACKAGE_CONTACT "jeff.h.delaune@jpl.nasa.gov") +set(CPACK_PACKAGE_VENDOR "JPL-California Institute of Technology") set(CPACK_PACKAGE_DESCRIPTION "Generic C++ library for vision-based navigation, with multi-sensor fusion capabilities for thermal, range, solar and GPS measurements.") set(CPACK_PACKAGE_DESCRIPTION_SUMMARY ${CPACK_PACKAGE_DESCRIPTION}) set(CPACK_PACKAGING_INSTALL_PREFIX ${CMAKE_INSTALL_PREFIX}) diff --git a/package.xml b/package.xml deleted file mode 100644 index 25251ff..0000000 --- a/package.xml +++ /dev/null @@ -1,14 +0,0 @@ - - x - 1.0.0 - Generic C++ library for vision-based navigation, with - multi-sensor fusion capabilities for thermal, range, solar and GPS - measurements. - Jeff Delaune - - California Institute of Technology - - catkin - cmake_modules - - From ca3bc366c5a5a5019dc84d547f5cf15c1679eb24 Mon Sep 17 00:00:00 2001 From: Vincenzo Polizzi Date: Tue, 19 Apr 2022 10:06:56 +0200 Subject: [PATCH 3/8] LUT for distortion --- .gitignore | 4 ++ include/x/vision/camera.h | 50 +++++++------- src/x/vision/camera.cpp | 138 +++++++++++++++++--------------------- 3 files changed, 89 insertions(+), 103 deletions(-) diff --git a/.gitignore b/.gitignore index dae7ac4..345c772 100644 --- a/.gitignore +++ b/.gitignore @@ -1,4 +1,5 @@ build +install # Temporary/backup files *~ *.sw* @@ -8,3 +9,6 @@ build # Formatting .clang-format + +CMakeCache.txt +CMakeFiles/* diff --git a/include/x/vision/camera.h b/include/x/vision/camera.h index f257944..333e11a 100644 --- a/include/x/vision/camera.h +++ b/include/x/vision/camera.h @@ -4,9 +4,9 @@ * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at - * + * * http://www.apache.org/licenses/LICENSE-2.0 - * + * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. @@ -17,52 +17,52 @@ #ifndef JPL_VPP_CAMERA_H_ #define JPL_VPP_CAMERA_H_ -#include -#include -#include "opencv2/highgui/highgui.hpp" +#include "x/vision/track.h" +#include "x/vision/types.h" + +#include +#include +#include -namespace x -{ -class Camera -{ +namespace x { +class Camera { public: Camera(); - Camera(double fx, - double fy, - double cx, - double cy, - double s, - unsigned int img_width, - unsigned int img_height); + Camera(double fx, double fy, double cx, double cy, double s, + unsigned int img_width, unsigned int img_height); unsigned int getWidth() const; unsigned int getHeight() const; double getInvFx() const; double getInvFy() const; double getCxN() const; double getCyN() const; - void undistort(FeatureList& features) const; - void undistort(Feature& feature) const; + void undistort(FeatureList &features) const; + void undistort(Feature &feature) const; // Returns image coordinates in normal plane - Feature normalize(const Feature& feature) const; - Track normalize(const Track& track, const size_t max_size = 0) const; - TrackList normalize(const TrackList& tracks, const size_t max_size = 0) const; + Feature normalize(const Feature &feature) const; + Track normalize(const Track &track, const size_t max_size = 0) const; + TrackList normalize(const TrackList &tracks, const size_t max_size = 0) const; + private: double fx_ = 0.0; // Focal length double fy_ = 0.0; double cx_ = 0.0; // Principal point double cy_ = 0.0; - double s_ = 0.0; // Distortion + double s_ = 0.0; // Distortion unsigned int img_width_ = 0.0; unsigned int img_height_ = 0.0; // Distortion terms we only want to compute once double inv_fx_ = -1; // Inverse focal length double inv_fy_ = -1; - double cx_n_ = -1; // Principal point in normalized coordinates - double cy_n_ = -1; + double cx_n_ = -1; // Principal point in normalized coordinates + double cy_n_ = -1; double s_term_ = -1; // Distortion term + + std::vector LUT_distortion_; + void populateLUT(); // Inverse FOV distortion transformation double inverseTf(const double dist) const; }; -} +} // namespace x #endif diff --git a/src/x/vision/camera.cpp b/src/x/vision/camera.cpp index 3565aa1..ed3f04a 100644 --- a/src/x/vision/camera.cpp +++ b/src/x/vision/camera.cpp @@ -4,9 +4,9 @@ * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at - * + * * http://www.apache.org/licenses/LICENSE-2.0 - * + * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. @@ -18,20 +18,11 @@ using namespace x; -Camera::Camera() -{} - -Camera::Camera(double fx, - double fy, - double cx, - double cy, - double s, - unsigned int img_width, - unsigned int img_height) -: s_(s) -, img_width_(img_width) -, img_height_(img_height) -{ +Camera::Camera() {} + +Camera::Camera(double fx, double fy, double cx, double cy, double s, + unsigned int img_width, unsigned int img_height) + : s_(s), img_width_(img_width), img_height_(img_height) { fx_ = img_width * fx; fy_ = img_height * fy; cx_ = img_width * cx; @@ -41,69 +32,62 @@ Camera::Camera(double fx, inv_fy_ = 1.0 / fy_; cx_n_ = cx_ * inv_fx_; cy_n_ = cy_ * inv_fy_; - s_term_ = 1.0 / ( 2.0 * std::tan(s / 2.0) ); + s_term_ = 1.0 / (2.0 * std::tan(s / 2.0)); + populateLUT(); } -unsigned int Camera::getWidth() const -{ - return img_width_; -} +void Camera::populateLUT() { + LUT_distortion_.reserve(img_width_ * img_height_); + for (int i = 0; i < img_width_; i++) { + for (int j = 0; j < img_height_; j++) { + const double cam_dist_x = i * inv_fx_ - cx_n_; + const double cam_dist_y = j * inv_fy_ - cy_n_; -unsigned int Camera::getHeight() const -{ - return img_height_; -} + const double dist_r = + sqrt(cam_dist_x * cam_dist_x + cam_dist_y * cam_dist_y); -double Camera::getInvFx() const -{ - return inv_fx_; -} + double distortion_factor = 1.0; + if (dist_r > 0.01) + distortion_factor = inverseTf(dist_r) / dist_r; -double Camera::getInvFy() const -{ - return inv_fy_; -} + const double xn = distortion_factor * cam_dist_x; + const double yn = distortion_factor * cam_dist_y; -double Camera::getCxN() const -{ - return cx_n_; + LUT_distortion_.emplace_back(cv::Point2d(xn * fx_ + cx_, yn * fy_ + cy_)); + } + } } -double Camera::getCyN() const -{ - return cy_n_; -} +unsigned int Camera::getWidth() const { return img_width_; } -void Camera::undistort(FeatureList& features) const -{ - // Undistort each point in the input vector - for(unsigned int i = 0; i < features.size(); i++) - undistort(features[i]); -} +unsigned int Camera::getHeight() const { return img_height_; } -void Camera::undistort(Feature& feature) const -{ - const double cam_dist_x = feature.getXDist() * inv_fx_ - cx_n_; - const double cam_dist_y = feature.getYDist() * inv_fy_ - cy_n_; +double Camera::getInvFx() const { return inv_fx_; } - const double dist_r = sqrt(cam_dist_x * cam_dist_x + cam_dist_y * cam_dist_y); +double Camera::getInvFy() const { return inv_fy_; } - double distortion_factor = 1.0; - if(dist_r > 0.01) - distortion_factor = inverseTf(dist_r) / dist_r; +double Camera::getCxN() const { return cx_n_; } - const double xn = distortion_factor * cam_dist_x; - const double yn = distortion_factor * cam_dist_y; +double Camera::getCyN() const { return cy_n_; } - feature.setX(xn * fx_ + cx_); - feature.setY(yn * fy_ + cy_); +void Camera::undistort(FeatureList &features) const { + // Undistort each point in the input vector + for (unsigned int i = 0; i < features.size(); i++) + undistort(features[i]); } -Feature Camera::normalize(const Feature& feature) const -{ +void Camera::undistort(Feature &feature) const { + const cv::Point2d f = + LUT_distortion_[static_cast(feature.getYDist() * img_width_) + + static_cast(feature.getXDist())]; + feature.setX(f.x); + feature.setY(f.y); +} + +Feature Camera::normalize(const Feature &feature) const { Feature normalized_feature(feature.getTimestamp(), - feature.getX() * inv_fx_ - cx_n_, - feature.getY() * inv_fy_ - cy_n_); + feature.getX() * inv_fx_ - cx_n_, + feature.getY() * inv_fy_ - cy_n_); normalized_feature.setXDist(feature.getXDist() * inv_fx_ - cx_n_); normalized_feature.setYDist(feature.getYDist() * inv_fx_ - cx_n_); @@ -112,15 +96,14 @@ Feature Camera::normalize(const Feature& feature) const /** \brief Normalized the image coordinates for all features in the input track * \param track Track to normalized - * \param max_size Max size of output track, cropping from the end (default 0: no cropping) - * \return Normalized track + * \param max_size Max size of output track, cropping from the end (default 0: + * no cropping) \return Normalized track */ -Track Camera::normalize(const Track& track, const size_t max_size) const -{ +Track Camera::normalize(const Track &track, const size_t max_size) const { // Determine output track size const size_t track_size = track.size(); size_t size_out; - if(max_size) + if (max_size) size_out = std::min(max_size, track_size); else size_out = track_size; @@ -129,29 +112,28 @@ Track Camera::normalize(const Track& track, const size_t max_size) const const size_t start_idx(track_size - size_out); for (size_t j = start_idx; j < track_size; ++j) normalized_track[j - start_idx] = normalize(track[j]); - + return normalized_track; } -/** \brief Normalized the image coordinates for all features in the input track list - * \param tracks List of tracks - * \param max_size Max size of output tracks, cropping from the end (default 0: no cropping) - * \return Normalized list of tracks +/** \brief Normalized the image coordinates for all features in the input track + * list \param tracks List of tracks \param max_size Max size of output tracks, + * cropping from the end (default 0: no cropping) \return Normalized list of + * tracks */ -TrackList Camera::normalize(const TrackList& tracks, const size_t max_size) const -{ +TrackList Camera::normalize(const TrackList &tracks, + const size_t max_size) const { const size_t n = tracks.size(); TrackList normalized_tracks(n, Track()); - + for (size_t i = 0; i < n; ++i) normalized_tracks[i] = normalize(tracks[i], max_size); return normalized_tracks; } -double Camera::inverseTf(const double dist) const -{ - if(s_ == 0.0) +double Camera::inverseTf(const double dist) const { + if (s_ == 0.0) return dist; else return std::tan(dist * s_) * s_term_; From f2d0a834d3b7c9738291da2c0bcc6189e4bafb89 Mon Sep 17 00:00:00 2001 From: Vincenzo Polizzi Date: Tue, 3 May 2022 22:59:27 +0200 Subject: [PATCH 4/8] LUT population --- src/x/vision/camera.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/x/vision/camera.cpp b/src/x/vision/camera.cpp index ed3f04a..1bb73e4 100644 --- a/src/x/vision/camera.cpp +++ b/src/x/vision/camera.cpp @@ -71,13 +71,13 @@ double Camera::getCxN() const { return cx_n_; } double Camera::getCyN() const { return cy_n_; } void Camera::undistort(FeatureList &features) const { - // Undistort each point in the input vector - for (unsigned int i = 0; i < features.size(); i++) - undistort(features[i]); + for (auto &f : features) { + undistort(f); + } } void Camera::undistort(Feature &feature) const { - const cv::Point2d f = + const auto f = LUT_distortion_[static_cast(feature.getYDist() * img_width_) + static_cast(feature.getXDist())]; feature.setX(f.x); From 4aff79b70bfbd91cb54336681a333a2fdee38476 Mon Sep 17 00:00:00 2001 From: Vincenzo Polizzi Date: Sat, 7 May 2022 16:56:44 +0200 Subject: [PATCH 5/8] c++17 --- CMakeLists.txt | 4 +--- src/x/vio/vio_updater.cpp | 39 ++++++++++++++------------------------- src/x/vision/camera.cpp | 39 +++++++++++++++++++++++++-------------- xConfig.cmake.in | 2 +- 4 files changed, 41 insertions(+), 43 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4cf2635..1dbd370 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -23,8 +23,6 @@ option(UNIT_TESTS "Publish std out and other data" OFF) # Set true to enable uni ################################################################################# -# set (CMAKE_BUILD_TYPE Release) - # Set definitions if(MULTI_THREAD) message("Multi-thread: ON") @@ -59,7 +57,7 @@ add_definitions(-DEIGEN_MATRIXBASE_PLUGIN=) find_package(Eigen3 REQUIRED) # Set build flags, depending on the architecture -set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14 -Wall") +set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17 -Wall") if (CMAKE_BUILD_TYPE MATCHES Release) message("Release Mode") diff --git a/src/x/vio/vio_updater.cpp b/src/x/vio/vio_updater.cpp index 3228939..fbbaefd 100644 --- a/src/x/vio/vio_updater.cpp +++ b/src/x/vio/vio_updater.cpp @@ -273,31 +273,20 @@ void VioUpdater::constructUpdate(const State& state, /* Combined update */ - const size_t rows_total - = rows_msckf + rows_msckf_slam + rows_slam + rows_lrf + rows_sns; - const size_t cols = P.cols(); - h = Matrix::Zero(rows_total, cols); - Eigen::VectorXd r_diag = Eigen::VectorXd::Ones(rows_total); - res = Matrix::Zero(rows_total, 1); - - h << h_msckf, - h_msckf_slam, - h_slam, - h_lrf, - h_sns; - - r_diag << r_msckf_diag, - r_msckf_slam_diag, - r_slam_diag, - r_lrf_diag, - r_sns_diag; - r = r_diag.asDiagonal(); - - res << res_msckf, - res_msckf_slam, - res_slam, - res_lrf, - res_sns; + const size_t rows_total = + rows_msckf + rows_msckf_slam + rows_slam + rows_lrf + rows_sns; + const size_t cols = P.cols(); + h = Matrix::Zero(rows_total, cols); + Eigen::VectorXd r_diag = Eigen::VectorXd::Ones(rows_total); + res = Matrix::Zero(rows_total, 1); + + h << h_msckf, h_msckf_slam, h_slam, h_lrf, h_sns; + + r_diag << r_msckf_diag, r_msckf_slam_diag, r_slam_diag, r_lrf_diag, + r_sns_diag; + r = r_diag.asDiagonal(); + + res << res_msckf, res_msckf_slam, res_slam, res_lrf, res_sns; // QR decomposition of the update Jacobian applyQRDecomposition(h, res, r); diff --git a/src/x/vision/camera.cpp b/src/x/vision/camera.cpp index 1bb73e4..c57d8e9 100644 --- a/src/x/vision/camera.cpp +++ b/src/x/vision/camera.cpp @@ -14,8 +14,8 @@ * limitations under the License. */ +#include #include - using namespace x; Camera::Camera() {} @@ -33,13 +33,13 @@ Camera::Camera(double fx, double fy, double cx, double cy, double s, cx_n_ = cx_ * inv_fx_; cy_n_ = cy_ * inv_fy_; s_term_ = 1.0 / (2.0 * std::tan(s / 2.0)); - populateLUT(); + // populateLUT(); } void Camera::populateLUT() { LUT_distortion_.reserve(img_width_ * img_height_); - for (int i = 0; i < img_width_; i++) { - for (int j = 0; j < img_height_; j++) { + for (size_t i = 0; i < img_width_; i++) { + for (size_t j = 0; j < img_height_; j++) { const double cam_dist_x = i * inv_fx_ - cx_n_; const double cam_dist_y = j * inv_fy_ - cy_n_; @@ -70,18 +70,29 @@ double Camera::getCxN() const { return cx_n_; } double Camera::getCyN() const { return cy_n_; } -void Camera::undistort(FeatureList &features) const { - for (auto &f : features) { - undistort(f); - } +void Camera::undistort(FeatureList& features) const +{ + // Undistort each point in the input vector + for(unsigned int i = 0; i < features.size(); i++) + undistort(features[i]); } -void Camera::undistort(Feature &feature) const { - const auto f = - LUT_distortion_[static_cast(feature.getYDist() * img_width_) + - static_cast(feature.getXDist())]; - feature.setX(f.x); - feature.setY(f.y); +void Camera::undistort(Feature& feature) const +{ + const double cam_dist_x = feature.getXDist() * inv_fx_ - cx_n_; + const double cam_dist_y = feature.getYDist() * inv_fy_ - cy_n_; + + const double dist_r = sqrt(cam_dist_x * cam_dist_x + cam_dist_y * cam_dist_y); + + double distortion_factor = 1.0; + if(dist_r > 0.01) + distortion_factor = inverseTf(dist_r) / dist_r; + + const double xn = distortion_factor * cam_dist_x; + const double yn = distortion_factor * cam_dist_y; + + feature.setX(xn * fx_ + cx_); + feature.setY(yn * fy_ + cy_); } Feature Camera::normalize(const Feature &feature) const { diff --git a/xConfig.cmake.in b/xConfig.cmake.in index 77942cc..6048145 100644 --- a/xConfig.cmake.in +++ b/xConfig.cmake.in @@ -50,7 +50,7 @@ check_required_components(x) LINK_DIRECTORIES("@CMAKE_INSTALL_PREFIX@/lib") set(@PROJECT_NAME@_LIB_DIR "@CMAKE_INSTALL_PREFIX@/lib") -set(@PROJECT_NAME@_LIBS @REQUIRED_LIBRARIES@ @PROJECT_NAME@@PROJECT_DLLVERSION@) +set(@PROJECT_NAME@_LIBRARIES @REQUIRED_LIBRARIES@ @PROJECT_NAME@@PROJECT_DLLVERSION@) set(@PROJECT_NAME@_FOUND YES) set(@PROJECT_NAME@_FOUND "YES") From a5dd30018edec8583e13d03e6e109e51f8e27ec5 Mon Sep 17 00:00:00 2001 From: Vincenzo Polizzi Date: Sat, 7 May 2022 17:45:47 +0200 Subject: [PATCH 6/8] Fixed eigen initialization issue causing chrushing in debug mode. x/y inversion in camera class. --- CMakeLists.txt | 1 - include/x/vision/camera.h | 50 ++++++++-------- src/x/vio/vio_updater.cpp | 2 +- src/x/vision/camera.cpp | 117 ++++++++++++++++++++------------------ 4 files changed, 88 insertions(+), 82 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 1dbd370..e129030 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -57,7 +57,6 @@ add_definitions(-DEIGEN_MATRIXBASE_PLUGIN=) find_package(Eigen3 REQUIRED) # Set build flags, depending on the architecture -set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17 -Wall") if (CMAKE_BUILD_TYPE MATCHES Release) message("Release Mode") diff --git a/include/x/vision/camera.h b/include/x/vision/camera.h index 333e11a..f257944 100644 --- a/include/x/vision/camera.h +++ b/include/x/vision/camera.h @@ -4,9 +4,9 @@ * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at - * + * * http://www.apache.org/licenses/LICENSE-2.0 - * + * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. @@ -17,52 +17,52 @@ #ifndef JPL_VPP_CAMERA_H_ #define JPL_VPP_CAMERA_H_ -#include "x/vision/track.h" -#include "x/vision/types.h" - -#include -#include -#include +#include +#include +#include "opencv2/highgui/highgui.hpp" -namespace x { -class Camera { +namespace x +{ +class Camera +{ public: Camera(); - Camera(double fx, double fy, double cx, double cy, double s, - unsigned int img_width, unsigned int img_height); + Camera(double fx, + double fy, + double cx, + double cy, + double s, + unsigned int img_width, + unsigned int img_height); unsigned int getWidth() const; unsigned int getHeight() const; double getInvFx() const; double getInvFy() const; double getCxN() const; double getCyN() const; - void undistort(FeatureList &features) const; - void undistort(Feature &feature) const; + void undistort(FeatureList& features) const; + void undistort(Feature& feature) const; // Returns image coordinates in normal plane - Feature normalize(const Feature &feature) const; - Track normalize(const Track &track, const size_t max_size = 0) const; - TrackList normalize(const TrackList &tracks, const size_t max_size = 0) const; - + Feature normalize(const Feature& feature) const; + Track normalize(const Track& track, const size_t max_size = 0) const; + TrackList normalize(const TrackList& tracks, const size_t max_size = 0) const; private: double fx_ = 0.0; // Focal length double fy_ = 0.0; double cx_ = 0.0; // Principal point double cy_ = 0.0; - double s_ = 0.0; // Distortion + double s_ = 0.0; // Distortion unsigned int img_width_ = 0.0; unsigned int img_height_ = 0.0; // Distortion terms we only want to compute once double inv_fx_ = -1; // Inverse focal length double inv_fy_ = -1; - double cx_n_ = -1; // Principal point in normalized coordinates - double cy_n_ = -1; + double cx_n_ = -1; // Principal point in normalized coordinates + double cy_n_ = -1; double s_term_ = -1; // Distortion term - - std::vector LUT_distortion_; - void populateLUT(); // Inverse FOV distortion transformation double inverseTf(const double dist) const; }; -} // namespace x +} #endif diff --git a/src/x/vio/vio_updater.cpp b/src/x/vio/vio_updater.cpp index fbbaefd..585273b 100644 --- a/src/x/vio/vio_updater.cpp +++ b/src/x/vio/vio_updater.cpp @@ -215,7 +215,7 @@ void VioUpdater::constructUpdate(const State& state, /* Range-SLAM */ size_t rows_lrf = 0; - Matrix h_lrf, res_lrf; + Matrix h_lrf = Matrix::Zero(0, P.cols()), res_lrf = Matrix::Zero(0, 1); Eigen::VectorXd r_lrf_diag; if (measurement_.range.timestamp > 0.1 && slam_trks_.size()) { diff --git a/src/x/vision/camera.cpp b/src/x/vision/camera.cpp index c57d8e9..bacfdc0 100644 --- a/src/x/vision/camera.cpp +++ b/src/x/vision/camera.cpp @@ -4,9 +4,9 @@ * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at - * + * * http://www.apache.org/licenses/LICENSE-2.0 - * + * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. @@ -14,15 +14,24 @@ * limitations under the License. */ -#include #include -using namespace x; -Camera::Camera() {} +using namespace x; -Camera::Camera(double fx, double fy, double cx, double cy, double s, - unsigned int img_width, unsigned int img_height) - : s_(s), img_width_(img_width), img_height_(img_height) { +Camera::Camera() +{} + +Camera::Camera(double fx, + double fy, + double cx, + double cy, + double s, + unsigned int img_width, + unsigned int img_height) +: s_(s) +, img_width_(img_width) +, img_height_(img_height) +{ fx_ = img_width * fx; fy_ = img_height * fy; cx_ = img_width * cx; @@ -32,43 +41,38 @@ Camera::Camera(double fx, double fy, double cx, double cy, double s, inv_fy_ = 1.0 / fy_; cx_n_ = cx_ * inv_fx_; cy_n_ = cy_ * inv_fy_; - s_term_ = 1.0 / (2.0 * std::tan(s / 2.0)); - // populateLUT(); + s_term_ = 1.0 / ( 2.0 * std::tan(s / 2.0) ); } -void Camera::populateLUT() { - LUT_distortion_.reserve(img_width_ * img_height_); - for (size_t i = 0; i < img_width_; i++) { - for (size_t j = 0; j < img_height_; j++) { - const double cam_dist_x = i * inv_fx_ - cx_n_; - const double cam_dist_y = j * inv_fy_ - cy_n_; - - const double dist_r = - sqrt(cam_dist_x * cam_dist_x + cam_dist_y * cam_dist_y); - - double distortion_factor = 1.0; - if (dist_r > 0.01) - distortion_factor = inverseTf(dist_r) / dist_r; - - const double xn = distortion_factor * cam_dist_x; - const double yn = distortion_factor * cam_dist_y; - - LUT_distortion_.emplace_back(cv::Point2d(xn * fx_ + cx_, yn * fy_ + cy_)); - } - } +unsigned int Camera::getWidth() const +{ + return img_width_; } -unsigned int Camera::getWidth() const { return img_width_; } - -unsigned int Camera::getHeight() const { return img_height_; } +unsigned int Camera::getHeight() const +{ + return img_height_; +} -double Camera::getInvFx() const { return inv_fx_; } +double Camera::getInvFx() const +{ + return inv_fx_; +} -double Camera::getInvFy() const { return inv_fy_; } +double Camera::getInvFy() const +{ + return inv_fy_; +} -double Camera::getCxN() const { return cx_n_; } +double Camera::getCxN() const +{ + return cx_n_; +} -double Camera::getCyN() const { return cy_n_; } +double Camera::getCyN() const +{ + return cy_n_; +} void Camera::undistort(FeatureList& features) const { @@ -95,26 +99,28 @@ void Camera::undistort(Feature& feature) const feature.setY(yn * fy_ + cy_); } -Feature Camera::normalize(const Feature &feature) const { +Feature Camera::normalize(const Feature& feature) const +{ Feature normalized_feature(feature.getTimestamp(), - feature.getX() * inv_fx_ - cx_n_, - feature.getY() * inv_fy_ - cy_n_); + feature.getX() * inv_fx_ - cx_n_, + feature.getY() * inv_fy_ - cy_n_); normalized_feature.setXDist(feature.getXDist() * inv_fx_ - cx_n_); - normalized_feature.setYDist(feature.getYDist() * inv_fx_ - cx_n_); + normalized_feature.setYDist(feature.getYDist() * inv_fy_ - cy_n_); return normalized_feature; } /** \brief Normalized the image coordinates for all features in the input track * \param track Track to normalized - * \param max_size Max size of output track, cropping from the end (default 0: - * no cropping) \return Normalized track + * \param max_size Max size of output track, cropping from the end (default 0: no cropping) + * \return Normalized track */ -Track Camera::normalize(const Track &track, const size_t max_size) const { +Track Camera::normalize(const Track& track, const size_t max_size) const +{ // Determine output track size const size_t track_size = track.size(); size_t size_out; - if (max_size) + if(max_size) size_out = std::min(max_size, track_size); else size_out = track_size; @@ -123,28 +129,29 @@ Track Camera::normalize(const Track &track, const size_t max_size) const { const size_t start_idx(track_size - size_out); for (size_t j = start_idx; j < track_size; ++j) normalized_track[j - start_idx] = normalize(track[j]); - + return normalized_track; } -/** \brief Normalized the image coordinates for all features in the input track - * list \param tracks List of tracks \param max_size Max size of output tracks, - * cropping from the end (default 0: no cropping) \return Normalized list of - * tracks +/** \brief Normalized the image coordinates for all features in the input track list + * \param tracks List of tracks + * \param max_size Max size of output tracks, cropping from the end (default 0: no cropping) + * \return Normalized list of tracks */ -TrackList Camera::normalize(const TrackList &tracks, - const size_t max_size) const { +TrackList Camera::normalize(const TrackList& tracks, const size_t max_size) const +{ const size_t n = tracks.size(); TrackList normalized_tracks(n, Track()); - + for (size_t i = 0; i < n; ++i) normalized_tracks[i] = normalize(tracks[i], max_size); return normalized_tracks; } -double Camera::inverseTf(const double dist) const { - if (s_ == 0.0) +double Camera::inverseTf(const double dist) const +{ + if(s_ == 0.0) return dist; else return std::tan(dist * s_) * s_term_; From 4ab76044419fb10bb836526ee4ebfbf980557312 Mon Sep 17 00:00:00 2001 From: Vincenzo Polizzi Date: Sat, 7 May 2022 17:49:38 +0200 Subject: [PATCH 7/8] Fixed eigen initialization issue causing chrushing in debug mode. x/y inversion in camera class. --- src/x/vio/vio_updater.cpp | 39 +++++++++++++++++++++++++-------------- 1 file changed, 25 insertions(+), 14 deletions(-) diff --git a/src/x/vio/vio_updater.cpp b/src/x/vio/vio_updater.cpp index 585273b..916721a 100644 --- a/src/x/vio/vio_updater.cpp +++ b/src/x/vio/vio_updater.cpp @@ -273,20 +273,31 @@ void VioUpdater::constructUpdate(const State& state, /* Combined update */ - const size_t rows_total = - rows_msckf + rows_msckf_slam + rows_slam + rows_lrf + rows_sns; - const size_t cols = P.cols(); - h = Matrix::Zero(rows_total, cols); - Eigen::VectorXd r_diag = Eigen::VectorXd::Ones(rows_total); - res = Matrix::Zero(rows_total, 1); - - h << h_msckf, h_msckf_slam, h_slam, h_lrf, h_sns; - - r_diag << r_msckf_diag, r_msckf_slam_diag, r_slam_diag, r_lrf_diag, - r_sns_diag; - r = r_diag.asDiagonal(); - - res << res_msckf, res_msckf_slam, res_slam, res_lrf, res_sns; + const size_t rows_total + = rows_msckf + rows_msckf_slam + rows_slam + rows_lrf + rows_sns; + const size_t cols = P.cols(); + h = Matrix::Zero(rows_total, cols); + Eigen::VectorXd r_diag = Eigen::VectorXd::Ones(rows_total); + res = Matrix::Zero(rows_total, 1); + + h << h_msckf, + h_msckf_slam, + h_slam, + h_lrf, + h_sns; + + r_diag << r_msckf_diag, + r_msckf_slam_diag, + r_slam_diag, + r_lrf_diag, + r_sns_diag; + r = r_diag.asDiagonal(); + + res << res_msckf, + res_msckf_slam, + res_slam, + res_lrf, + res_sns; // QR decomposition of the update Jacobian applyQRDecomposition(h, res, r); From 7cbae8bd64bc04fbb7adcae4385424793e9fd50a Mon Sep 17 00:00:00 2001 From: Vincenzo Polizzi Date: Sat, 7 May 2022 18:04:11 +0200 Subject: [PATCH 8/8] Cleaned CmakeLists option information --- CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 98b3f58..9628f04 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,12 +14,12 @@ OPTION(MULTI_THREAD "Multi thread" ON) # Set true to process image and inertial option(VERBOSE "Publish std out and other data" ON) # Set false to disable all publishing and standard output # stream, except pose at update rate. That will improve runtime. -option(TIMING "Publish std out and other data" OFF) # Set true to enable timers +option(TIMING "Publish timing information" OFF) # Set true to enable timers -option(PROFILING "Publish std out and other data" OFF) # Set true to disable compiler flags which are not +option(PROFILING "Enable profiling flags" OFF) # Set true to disable compiler flags which are not # compatible with Callgrind profiling tool. -option(UNIT_TESTS "Publish std out and other data" OFF) # Set true to enable unit tests +option(UNIT_TESTS "Build unit tests" OFF) # Set true to enable unit tests #################################################################################