diff --git a/CMakeLists.txt b/CMakeLists.txt index 44c930be..a77873c9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -34,6 +34,12 @@ set(EXTERNAL_LIBRARIES_DIRECTORY ${REPOSITORY_DIRECTORY}/external) set(HD_CPU_OPTIMIZATION "AUTO" CACHE STRING "CPU optimization target (AUTO, INTEL, AMD, ARM, GENERIC)") set_property(CACHE HD_CPU_OPTIMIZATION PROPERTY STRINGS AUTO INTEL AMD ARM GENERIC) +if(APPLE AND CMAKE_CXX_COMPILER_ID STREQUAL "AppleClang") + add_compile_definitions(USE_EXECUTION_PAR_UNSEQ=0) +else() + add_compile_definitions(USE_EXECUTION_PAR_UNSEQ=1) +endif() + if (MSVC) add_definitions(-D_HAS_STD_BYTE=0) diff --git a/apps/compare_trajectories/mandeye_compare_trajectories.cpp b/apps/compare_trajectories/mandeye_compare_trajectories.cpp index 83d43314..4f9c6fa6 100644 --- a/apps/compare_trajectories/mandeye_compare_trajectories.cpp +++ b/apps/compare_trajectories/mandeye_compare_trajectories.cpp @@ -15,7 +15,7 @@ #include -#include +#include #include diff --git a/apps/concatenate_multi_livox/concatenate_multi_livox.cpp b/apps/concatenate_multi_livox/concatenate_multi_livox.cpp index 2e094887..7022a5ef 100644 --- a/apps/concatenate_multi_livox/concatenate_multi_livox.cpp +++ b/apps/concatenate_multi_livox/concatenate_multi_livox.cpp @@ -1,5 +1,5 @@ #include "../lidar_odometry_step_1/lidar_odometry_utils.h" -#include "export_laz.h" +#include #include #include diff --git a/apps/console_tools/matrix_mul.cpp b/apps/console_tools/matrix_mul.cpp index 02c7109c..9f453ed9 100644 --- a/apps/console_tools/matrix_mul.cpp +++ b/apps/console_tools/matrix_mul.cpp @@ -1,8 +1,9 @@ #include #include #include -#include -#include + +#include +#include int main(int argc, char* argv[]) { diff --git a/apps/console_tools/multiply_timestamps_session_point_cloud_laz.cpp b/apps/console_tools/multiply_timestamps_session_point_cloud_laz.cpp index e37de472..73217f0d 100644 --- a/apps/console_tools/multiply_timestamps_session_point_cloud_laz.cpp +++ b/apps/console_tools/multiply_timestamps_session_point_cloud_laz.cpp @@ -1,15 +1,14 @@ #include #include #include -#include -#include -#include +#include +#include +#include +#include #include -#include - #include bool load_pc(PointCloud& pc, const std::string& input_file_name) diff --git a/apps/console_tools/multiply_timestamps_session_trajectory_csv.cpp b/apps/console_tools/multiply_timestamps_session_trajectory_csv.cpp index e5b938d6..e734ea48 100644 --- a/apps/console_tools/multiply_timestamps_session_trajectory_csv.cpp +++ b/apps/console_tools/multiply_timestamps_session_trajectory_csv.cpp @@ -1,10 +1,10 @@ #include #include #include -#include -#include -#include +#include +#include +#include inline void split(std::string& str, char delim, std::vector& out) { diff --git a/apps/lidar_odometry_step_1/drag_folder_with_mandeye_data_and_drop_here-precision_forestry.cpp b/apps/lidar_odometry_step_1/drag_folder_with_mandeye_data_and_drop_here-precision_forestry.cpp index cde46174..0e2608bb 100644 --- a/apps/lidar_odometry_step_1/drag_folder_with_mandeye_data_and_drop_here-precision_forestry.cpp +++ b/apps/lidar_odometry_step_1/drag_folder_with_mandeye_data_and_drop_here-precision_forestry.cpp @@ -12,19 +12,18 @@ #include "lidar_odometry.h" #include "lidar_odometry_utils.h" -#include -#include -#include +#include +#include +#include +#include +#include #include "toml_io.h" #include #include #include -#include #include -#include -#include #include #include diff --git a/apps/lidar_odometry_step_1/lidar_odometry.cpp b/apps/lidar_odometry_step_1/lidar_odometry.cpp index e5b65745..acc02811 100644 --- a/apps/lidar_odometry_step_1/lidar_odometry.cpp +++ b/apps/lidar_odometry_step_1/lidar_odometry.cpp @@ -2,7 +2,8 @@ #include "tbb/tbb.h" #include #include -#include + +#include namespace fs = std::filesystem; diff --git a/apps/lidar_odometry_step_1/lidar_odometry.h b/apps/lidar_odometry_step_1/lidar_odometry.h index c93944a5..e080ecb8 100644 --- a/apps/lidar_odometry_step_1/lidar_odometry.h +++ b/apps/lidar_odometry_step_1/lidar_odometry.h @@ -6,10 +6,11 @@ #include "lidar_odometry_utils.h" #include "toml_io.h" #include -#include #include #include -#include + +#include +#include // #define SAMPLE_PERIOD (1.0 / 200.0) diff --git a/apps/lidar_odometry_step_1/lidar_odometry_gui.cpp b/apps/lidar_odometry_step_1/lidar_odometry_gui.cpp index 5ffb9a98..363735ab 100644 --- a/apps/lidar_odometry_step_1/lidar_odometry_gui.cpp +++ b/apps/lidar_odometry_step_1/lidar_odometry_gui.cpp @@ -12,19 +12,18 @@ #include "lidar_odometry.h" #include "lidar_odometry_utils.h" -#include -#include -#include +#include +#include +#include +#include +#include #include "toml_io.h" #include #include #include -#include #include -#include -#include #include #include diff --git a/apps/lidar_odometry_step_1/lidar_odometry_utils.cpp b/apps/lidar_odometry_step_1/lidar_odometry_utils.cpp index 44512477..b95cc2ba 100644 --- a/apps/lidar_odometry_step_1/lidar_odometry_utils.cpp +++ b/apps/lidar_odometry_step_1/lidar_odometry_utils.cpp @@ -2,11 +2,12 @@ #include "csv.hpp" #include #include -#include #include #include #include +#include + #include namespace fs = std::filesystem; diff --git a/apps/lidar_odometry_step_1/lidar_odometry_utils.h b/apps/lidar_odometry_step_1/lidar_odometry_utils.h index 8491497d..34a3ae72 100644 --- a/apps/lidar_odometry_step_1/lidar_odometry_utils.h +++ b/apps/lidar_odometry_step_1/lidar_odometry_utils.h @@ -14,10 +14,11 @@ #include #include #include -#include #include -#include -#include + +#include +#include +#include #include #include diff --git a/apps/lidar_odometry_step_1/lidar_odometry_utils_optimizers.cpp b/apps/lidar_odometry_step_1/lidar_odometry_utils_optimizers.cpp index 5d33b71e..bedb70e3 100644 --- a/apps/lidar_odometry_step_1/lidar_odometry_utils_optimizers.cpp +++ b/apps/lidar_odometry_step_1/lidar_odometry_utils_optimizers.cpp @@ -1,13 +1,13 @@ #include "lidar_odometry_utils.h" #include -#include #include #include #include #include #include -#include +#include +#include const double DEG_TO_RAD = M_PI / 180.0f; const double RAD_TO_DEG = 180.0f / M_PI; @@ -598,7 +598,13 @@ void optimize_sf( { // spdlog::info("start adding lidar observations"); if (multithread) - std::for_each(std::execution::par_unseq, std::begin(points_local), std::end(points_local), hessian_fun); + std::for_each( +#if USE_EXECUTION_PAR_UNSEQ + std::execution::par_unseq, +#endif + std::begin(points_local), + std::end(points_local), + hessian_fun); else std::for_each(std::begin(points_local), std::end(points_local), hessian_fun); // spdlog::info("adding lidar observations finished"); @@ -915,7 +921,14 @@ void optimize_sf2( std::vector AtPAndtBlocksToSum(intermediate_points.size()); if (useMultithread) - std::transform(std::execution::par_unseq, std::begin(indexes), std::end(indexes), std::begin(AtPAndtBlocksToSum), hessian_fun); + std::transform( +#if USE_EXECUTION_PAR_UNSEQ + std::execution::par_unseq, +#endif + std::begin(indexes), + std::end(indexes), + std::begin(AtPAndtBlocksToSum), + hessian_fun); else std::transform(std::begin(indexes), std::end(indexes), std::begin(AtPAndtBlocksToSum), hessian_fun); @@ -1303,7 +1316,14 @@ void optimize_rigid_sf( std::vector blocks(indexes.size()); if (useMultithread) // ToDo fix for this case - std::transform(std::execution::par_unseq, std::begin(indexes), std::end(indexes), std::begin(blocks), hessian_fun); + std::transform( +#if USE_EXECUTION_PAR_UNSEQ + std::execution::par_unseq, +#endif + std::begin(indexes), + std::end(indexes), + std::begin(blocks), + hessian_fun); else std::transform(std::begin(indexes), std::end(indexes), std::begin(blocks), hessian_fun); @@ -3306,7 +3326,13 @@ void Consistency(std::vector& worker_data, const LidarOdometryParams }; if (multithread) - std::for_each(std::execution::par_unseq, std::begin(points_local), std::end(points_local), hessian_fun); + std::for_each( +#if USE_EXECUTION_PAR_UNSEQ + std::execution::par_unseq, +#endif + std::begin(points_local), + std::end(points_local), + hessian_fun); else std::for_each(std::begin(points_local), std::end(points_local), hessian_fun); diff --git a/apps/livox_mid_360_intrinsic_calibration/livox_mid_360_intrinsic_calibration.cpp b/apps/livox_mid_360_intrinsic_calibration/livox_mid_360_intrinsic_calibration.cpp index 2a9f677d..c4bb4b09 100644 --- a/apps/livox_mid_360_intrinsic_calibration/livox_mid_360_intrinsic_calibration.cpp +++ b/apps/livox_mid_360_intrinsic_calibration/livox_mid_360_intrinsic_calibration.cpp @@ -15,20 +15,16 @@ #include -#include - -#include "pfd_wrapper.hpp" +#include +#include +#include +#include +#include #include "../lidar_odometry_step_1/lidar_odometry_utils.h" #include -#include - -#include - -#include - #include #include @@ -1530,7 +1526,13 @@ void calibrate_intrinsics() std::cout << "start adding lidar observations" << std::endl; if (multithread) { - std::for_each(std::execution::par_unseq, std::begin(point_cloud), std::end(point_cloud), hessian_fun); + std::for_each( +#if USE_EXECUTION_PAR_UNSEQ + std::execution::par_unseq, +#endif + std::begin(point_cloud), + std::end(point_cloud), + hessian_fun); } else { diff --git a/apps/mandeye_mission_recorder_calibration/mandeye_mission_recorder_calibration.cpp b/apps/mandeye_mission_recorder_calibration/mandeye_mission_recorder_calibration.cpp index c3880bb9..8d5869c7 100644 --- a/apps/mandeye_mission_recorder_calibration/mandeye_mission_recorder_calibration.cpp +++ b/apps/mandeye_mission_recorder_calibration/mandeye_mission_recorder_calibration.cpp @@ -13,14 +13,9 @@ #include #include -#include #include -#include - -#include "pfd_wrapper.hpp" - #include "../lidar_odometry_step_1/lidar_odometry_utils.h" #include @@ -28,7 +23,10 @@ #include -#include +#include +#include +#include +#include #ifdef _WIN32 #include "resource.h" @@ -36,8 +34,6 @@ #include #endif -#include - /////////////////////////////////////////////////////////////////////////////////// std::string winTitle = std::string("MR calibration ") + HDMAPPING_VERSION_STRING; diff --git a/apps/mandeye_raw_data_viewer/mandeye_raw_data_viewer.cpp b/apps/mandeye_raw_data_viewer/mandeye_raw_data_viewer.cpp index 2d20aa42..66be38b4 100644 --- a/apps/mandeye_raw_data_viewer/mandeye_raw_data_viewer.cpp +++ b/apps/mandeye_raw_data_viewer/mandeye_raw_data_viewer.cpp @@ -13,13 +13,14 @@ #include #include -#include -#include - -#include +#include +#include +#include +#include +#include -#include "pfd_wrapper.hpp" +#include #include "../lidar_odometry_step_1/lidar_odometry.h" #include "../lidar_odometry_step_1/lidar_odometry_utils.h" @@ -30,12 +31,8 @@ #include "tbb/tbb.h" #include -#include - #include -#include - #ifdef _WIN32 #include "resource.h" #include // <-- Required for ShellExecuteA diff --git a/apps/mandeye_single_session_viewer/mandeye_single_session_viewer.cpp b/apps/mandeye_single_session_viewer/mandeye_single_session_viewer.cpp index 86da4ec6..fa339884 100644 --- a/apps/mandeye_single_session_viewer/mandeye_single_session_viewer.cpp +++ b/apps/mandeye_single_session_viewer/mandeye_single_session_viewer.cpp @@ -14,13 +14,13 @@ #include #include -#include -#include - -#include +#include +#include +#include +#include -#include "pfd_wrapper.hpp" +#include #include "../lidar_odometry_step_1/lidar_odometry_utils.h" #include @@ -34,7 +34,6 @@ #include // <-- Required for ShellExecuteA #include #endif -#include /////////////////////////////////////////////////////////////////////////////////// diff --git a/apps/manual_color/manual_color.cpp b/apps/manual_color/manual_color.cpp index 0cc51e54..2c187642 100644 --- a/apps/manual_color/manual_color.cpp +++ b/apps/manual_color/manual_color.cpp @@ -1,4 +1,3 @@ - #include #include @@ -8,25 +7,27 @@ #define STB_IMAGE_IMPLEMENTATION #include "stb_image.h" -#include -#include #include #include +#include #include -#include +#include #include - -#include "color_las_loader.h" -#include "pfd_wrapper.hpp" -#include +#include +#include #include +#include + +#include +#include +#include +#include + #include #include #include -#include -#include #include @@ -368,7 +369,9 @@ std::vector ApplyColorToPointcloud( { std::vector newCloud(pointsRGB.size()); std::transform( +#if USE_EXECUTION_PAR_UNSEQ std::execution::par_unseq, +#endif pointsRGB.begin(), pointsRGB.end(), newCloud.begin(), @@ -416,7 +419,9 @@ std::vector ApplyColorToPointcloudFishEye( { std::vector newCloud(pointsRGB.size()); std::transform( +#if USE_EXECUTION_PAR_UNSEQ std::execution::par_unseq, +#endif pointsRGB.begin(), pointsRGB.end(), newCloud.begin(), @@ -1357,7 +1362,9 @@ void mouse(int glut_button, int state, int x, int y) std::pair distanceIndexPair{ std::numeric_limits::max(), -1 }; std::for_each( +#if USE_EXECUTION_PAR_UNSEQ std::execution::par_unseq, +#endif SystemData::points.begin(), SystemData::points.end(), [&](const mandeye::PointRGB& p) diff --git a/apps/multi_session_registration/multi_session_factor_graph.cpp b/apps/multi_session_registration/multi_session_factor_graph.cpp index 6b0ceb27..780c17d7 100644 --- a/apps/multi_session_registration/multi_session_factor_graph.cpp +++ b/apps/multi_session_registration/multi_session_factor_graph.cpp @@ -1,7 +1,7 @@ #include "multi_session_factor_graph.h" -#include -#include +#include +#include #include #include diff --git a/apps/multi_session_registration/multi_session_factor_graph.h b/apps/multi_session_registration/multi_session_factor_graph.h index a911ffd1..3d301add 100644 --- a/apps/multi_session_registration/multi_session_factor_graph.h +++ b/apps/multi_session_registration/multi_session_factor_graph.h @@ -1,6 +1,6 @@ #pragma once -#include +#include struct Edge { diff --git a/apps/multi_session_registration/multi_session_registration.cpp b/apps/multi_session_registration/multi_session_registration.cpp index 417791e6..fd56b92f 100644 --- a/apps/multi_session_registration/multi_session_registration.cpp +++ b/apps/multi_session_registration/multi_session_registration.cpp @@ -17,26 +17,20 @@ #include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include -#include #include -#include - -#include - -#include - #include -#include - -#include -#include - -#include - #ifdef _WIN32 #include "resource.h" #include diff --git a/apps/multi_view_tls_registration/multi_view_tls_registration.cpp b/apps/multi_view_tls_registration/multi_view_tls_registration.cpp index eaa35911..a64b0325 100644 --- a/apps/multi_view_tls_registration/multi_view_tls_registration.cpp +++ b/apps/multi_view_tls_registration/multi_view_tls_registration.cpp @@ -1,5 +1,5 @@ #include "multi_view_tls_registration.h" -#include +#include #include #include diff --git a/apps/multi_view_tls_registration/multi_view_tls_registration.h b/apps/multi_view_tls_registration/multi_view_tls_registration.h index 2f858dfd..0553abb5 100644 --- a/apps/multi_view_tls_registration/multi_view_tls_registration.h +++ b/apps/multi_view_tls_registration/multi_view_tls_registration.h @@ -2,14 +2,15 @@ #pragma once #include -#include -#include -#include -#include #include -#include -#include -#include + +#include +#include +#include +#include +#include +#include +#include namespace fs = std::filesystem; diff --git a/apps/multi_view_tls_registration/multi_view_tls_registration_gui.cpp b/apps/multi_view_tls_registration/multi_view_tls_registration_gui.cpp index acae4371..d077b0f4 100644 --- a/apps/multi_view_tls_registration/multi_view_tls_registration_gui.cpp +++ b/apps/multi_view_tls_registration/multi_view_tls_registration_gui.cpp @@ -9,21 +9,26 @@ #include +#include + #include #include #include -#include -#include -#include -#include -#include -#include - -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include @@ -36,17 +41,11 @@ #include "../lidar_odometry_step_1/lidar_odometry_utils.h" #include "multi_view_tls_registration.h" -#include - -#include -#include -#include #include #include "WGS84toCartesian.hpp" #include "wgs84_do_puwg92.h" -#include #include #ifdef _WIN32 diff --git a/apps/multi_view_tls_registration/perform_experiment.cpp b/apps/multi_view_tls_registration/perform_experiment.cpp index f2b4601f..3d09d804 100644 --- a/apps/multi_view_tls_registration/perform_experiment.cpp +++ b/apps/multi_view_tls_registration/perform_experiment.cpp @@ -1,4 +1,7 @@ #include +#include +#include +#include // clang-format off #include @@ -17,26 +20,20 @@ #include #include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include #include -#include -#include -#include - -#include - -#include -#include - #include namespace fs = std::filesystem; diff --git a/apps/precision_forestry_tools/CMakeLists.txt b/apps/precision_forestry_tools/CMakeLists.txt index a2ede28f..afc596e2 100644 --- a/apps/precision_forestry_tools/CMakeLists.txt +++ b/apps/precision_forestry_tools/CMakeLists.txt @@ -4,9 +4,8 @@ project(precision_forestry_tools) add_executable(precision_forestry_tools precision_forestry_tools.cpp - ${REPOSITORY_DIRECTORY}/core/src/local_shape_features.cpp - ${REPOSITORY_DIRECTORY}/core/src/surface.cpp - ${REPOSITORY_DIRECTORY}/core/src/hash_utils.cpp) + surface.cpp + local_shape_features.cpp) target_compile_definitions(precision_forestry_tools PRIVATE -DWITH_GUI=1) diff --git a/core/src/local_shape_features.cpp b/apps/precision_forestry_tools/local_shape_features.cpp similarity index 95% rename from core/src/local_shape_features.cpp rename to apps/precision_forestry_tools/local_shape_features.cpp index b325a6c2..4e430fd7 100644 --- a/core/src/local_shape_features.cpp +++ b/apps/precision_forestry_tools/local_shape_features.cpp @@ -1,7 +1,8 @@ -#include +#include -#include -#include +#include "local_shape_features.h" + +#include bool LocalShapeFeatures::calculate_local_shape_features(std::vector& points, const Params& params) { @@ -130,7 +131,13 @@ bool LocalShapeFeatures::calculate_local_shape_features(std::vector -#include "pfd_wrapper.hpp" - #include -#include -#include -#include -#include + +#include +#include +#include #include #include #include +#include "local_shape_features.h" +#include "surface.h" + const uint32_t window_width = 800; const uint32_t window_height = 600; double camera_ortho_xy_view_zoom = 10; diff --git a/core/src/surface.cpp b/apps/precision_forestry_tools/surface.cpp similarity index 98% rename from core/src/surface.cpp rename to apps/precision_forestry_tools/surface.cpp index 3a12ee02..a7ad54c8 100644 --- a/core/src/surface.cpp +++ b/apps/precision_forestry_tools/surface.cpp @@ -1,12 +1,11 @@ -#include - -#include +#include "surface.h" #include -#include -#include +#include +#include +// TODO(mwlasiuk) : fix includes #include <../../3rdparty/observation_equations/codes/common/include/cauchy.h> #include <../../3rdparty/observation_equations/codes/python-scripts/constraints/relative_pose_tait_bryan_wc_jacobian.h> #include <../../3rdparty/observation_equations/codes/python-scripts/point-to-point-metrics/point_to_point_source_to_target_tait_bryan_wc_jacobian.h> @@ -537,7 +536,13 @@ std::vector Surface::get_filtered_indexes( if (multithread) { - std::for_each(std::execution::par_unseq, std::begin(indexes), std::end(indexes), hessian_fun); + std::for_each( +#if USE_EXECUTION_PAR_UNSEQ + std::execution::par_unseq, +#endif + std::begin(indexes), + std::end(indexes), + hessian_fun); } else { diff --git a/core/include/surface.h b/apps/precision_forestry_tools/surface.h similarity index 84% rename from core/include/surface.h rename to apps/precision_forestry_tools/surface.h index 1a5065cd..b005cb7f 100644 --- a/core/include/surface.h +++ b/apps/precision_forestry_tools/surface.h @@ -3,26 +3,13 @@ #include #include -#include +#include class Surface { public: - // struct TripletIndexes - //{ - // int index_before; - // int index_curr; - // int index_after; - // }; - - Surface() - { - ; - }; - ~Surface() - { - ; - }; + Surface() = default; + ~Surface() = default; std::vector vertices; std::vector vertices_odo; diff --git a/apps/quick_start_demo/quick_start_demo.cpp b/apps/quick_start_demo/quick_start_demo.cpp index 0ab13b2f..0caa445d 100644 --- a/apps/quick_start_demo/quick_start_demo.cpp +++ b/apps/quick_start_demo/quick_start_demo.cpp @@ -853,7 +853,11 @@ int main(int argc, char *argv[]) std::mutex mtx; std::cout << "start std::transform" << std::endl; - std::transform(std::execution::par_unseq, std::begin(laz_files), std::end(laz_files), std::begin(pointsPerFile), [&](const std::string &fn) + std::transform( + #if USE_EXECUTION_PAR_UNSEQ + std::execution::par_unseq, + #endif + std::begin(laz_files), std::end(laz_files), std::begin(pointsPerFile), [&](const std::string &fn) { // Load mapping from id to sn fs::path fnSn(fn); diff --git a/apps/single_session_manual_coloring/single_session_manual_coloring.cpp b/apps/single_session_manual_coloring/single_session_manual_coloring.cpp index 3279d83d..444317a9 100644 --- a/apps/single_session_manual_coloring/single_session_manual_coloring.cpp +++ b/apps/single_session_manual_coloring/single_session_manual_coloring.cpp @@ -7,32 +7,30 @@ #define STB_IMAGE_IMPLEMENTATION #include "stb_image.h" -#include -#include -#include "color_las_loader.h" -#include "pfd_wrapper.hpp" -#include +#include +#include +#include +#include +#include +#include #include + #include #include #include -#include -#include #include #include #include -#include - -#include - #include #include #include +#include +#include const uint32_t window_width = 800; const uint32_t window_height = 600; @@ -176,7 +174,9 @@ std::vector ApplyColorToPointcloud( { std::vector newCloud(pointsRGB.size()); std::transform( +#if USE_EXECUTION_PAR_UNSEQ std::execution::par_unseq, +#endif pointsRGB.begin(), pointsRGB.end(), newCloud.begin(), diff --git a/apps/split_multi_livox/split_multi_livox.cpp b/apps/split_multi_livox/split_multi_livox.cpp index 406b35e3..a82bdde0 100644 --- a/apps/split_multi_livox/split_multi_livox.cpp +++ b/apps/split_multi_livox/split_multi_livox.cpp @@ -1,12 +1,13 @@ -#include +#include #include -#include + #include #include -#include #include #include +#include +#include #include struct Point3Dis diff --git a/core/CMakeLists.txt b/core/CMakeLists.txt index 19969006..d6109a6e 100644 --- a/core/CMakeLists.txt +++ b/core/CMakeLists.txt @@ -23,6 +23,7 @@ set(CORE_BASE_SOURCES src/pose_graph_slam.cpp src/registration_plane_feature.cpp src/session.cpp + # src/utils.cpp # TODO(mwlasiuk) : broken AF ... ${EXTERNAL_LIBRARIES_DIRECTORY}/src/wgs84_do_puwg92.cc ${EXTERNAL_LIBRARIES_DIRECTORY}/src/plycpp.cpp ) diff --git a/core/include/GL_assert.h b/core/include/Core/GL_assert.h similarity index 100% rename from core/include/GL_assert.h rename to core/include/Core/GL_assert.h diff --git a/core/include/color_las_loader.h b/core/include/Core/color_las_loader.h similarity index 100% rename from core/include/color_las_loader.h rename to core/include/Core/color_las_loader.h diff --git a/core/include/control_points.h b/core/include/Core/control_points.h similarity index 97% rename from core/include/control_points.h rename to core/include/Core/control_points.h index f9eff83a..c674344c 100644 --- a/core/include/control_points.h +++ b/core/include/Core/control_points.h @@ -1,6 +1,7 @@ #pragma once -#include +#include + #include #include #if WITH_GUI == 1 diff --git a/core/include/exportPcd.h b/core/include/Core/exportPcd.h similarity index 100% rename from core/include/exportPcd.h rename to core/include/Core/exportPcd.h diff --git a/core/include/export_laz.h b/core/include/Core/export_laz.h similarity index 99% rename from core/include/export_laz.h rename to core/include/Core/export_laz.h index f35f9478..9ace206f 100644 --- a/core/include/export_laz.h +++ b/core/include/Core/export_laz.h @@ -2,9 +2,10 @@ // TODO(mwlasiuk) : do this at the end (print -> spdlog) as it is .h and not cpp + hpp and that breaks some subprojects ... +#include + #include #include -#include #include #include diff --git a/core/include/fmt_filesystem.hpp b/core/include/Core/fmt_filesystem.hpp similarity index 100% rename from core/include/fmt_filesystem.hpp rename to core/include/Core/fmt_filesystem.hpp diff --git a/core/include/gnss.h b/core/include/Core/gnss.h similarity index 99% rename from core/include/gnss.h rename to core/include/Core/gnss.h index 2bae2916..19227211 100644 --- a/core/include/gnss.h +++ b/core/include/Core/gnss.h @@ -1,6 +1,6 @@ #pragma once -#include +#include #include #include diff --git a/core/include/ground_control_points.h b/core/include/Core/ground_control_points.h similarity index 97% rename from core/include/ground_control_points.h rename to core/include/Core/ground_control_points.h index e0b0966d..ed23ef71 100644 --- a/core/include/ground_control_points.h +++ b/core/include/Core/ground_control_points.h @@ -1,6 +1,6 @@ #pragma once -#include +#include #include #include diff --git a/core/include/hash_utils.h b/core/include/Core/hash_utils.h similarity index 100% rename from core/include/hash_utils.h rename to core/include/Core/hash_utils.h diff --git a/core/include/icp.h b/core/include/Core/icp.h similarity index 99% rename from core/include/icp.h rename to core/include/Core/icp.h index 187dcea9..08cb9210 100644 --- a/core/include/icp.h +++ b/core/include/Core/icp.h @@ -1,6 +1,7 @@ #pragma once -#include +#include + #include class ICP diff --git a/core/include/m_estimators.h b/core/include/Core/m_estimators.h similarity index 100% rename from core/include/m_estimators.h rename to core/include/Core/m_estimators.h diff --git a/core/include/manual_pose_graph_loop_closure.h b/core/include/Core/manual_pose_graph_loop_closure.h similarity index 87% rename from core/include/manual_pose_graph_loop_closure.h rename to core/include/Core/manual_pose_graph_loop_closure.h index adc217b5..295360fc 100644 --- a/core/include/manual_pose_graph_loop_closure.h +++ b/core/include/Core/manual_pose_graph_loop_closure.h @@ -3,11 +3,13 @@ #if WITH_GUI == 1 #include -#include + #include -#include -#include -#include + +#include +#include +#include +#include class ManualPoseGraphLoopClosure : public PoseGraphLoopClosure { diff --git a/core/include/ndt.h b/core/include/Core/ndt.h similarity index 99% rename from core/include/ndt.h rename to core/include/Core/ndt.h index 4a11b207..8ed338c4 100644 --- a/core/include/ndt.h +++ b/core/include/Core/ndt.h @@ -1,8 +1,9 @@ #pragma once +#include +#include + #include -#include -#include #include class NDT diff --git a/core/include/nmea.h b/core/include/Core/nmea.h similarity index 100% rename from core/include/nmea.h rename to core/include/Core/nmea.h diff --git a/core/include/observation_picking.h b/core/include/Core/observation_picking.h similarity index 98% rename from core/include/observation_picking.h rename to core/include/Core/observation_picking.h index fe44fa9a..cefb7b09 100644 --- a/core/include/observation_picking.h +++ b/core/include/Core/observation_picking.h @@ -1,12 +1,13 @@ #pragma once +#include +#include + #include #include #include #include #include -#include -#include struct PointInsideIntersection { diff --git a/core/include/pair_wise_iterative_closest_point.h b/core/include/Core/pair_wise_iterative_closest_point.h similarity index 100% rename from core/include/pair_wise_iterative_closest_point.h rename to core/include/Core/pair_wise_iterative_closest_point.h diff --git a/core/include/pfd_wrapper.hpp b/core/include/Core/pfd_wrapper.hpp similarity index 100% rename from core/include/pfd_wrapper.hpp rename to core/include/Core/pfd_wrapper.hpp diff --git a/core/include/point_cloud.h b/core/include/Core/point_cloud.h similarity index 98% rename from core/include/point_cloud.h rename to core/include/Core/point_cloud.h index a00bd53e..dce5de80 100644 --- a/core/include/point_cloud.h +++ b/core/include/Core/point_cloud.h @@ -1,13 +1,15 @@ #pragma once #include + #include -#include #include +#include + #if WITH_GUI == 1 +#include #include -#include #endif class PointCloud diff --git a/core/include/point_clouds.h b/core/include/Core/point_clouds.h similarity index 97% rename from core/include/point_clouds.h rename to core/include/Core/point_clouds.h index f8c1ab78..b9aa988d 100644 --- a/core/include/point_clouds.h +++ b/core/include/Core/point_clouds.h @@ -3,10 +3,11 @@ #include #include -#include -#include +#include +#include + #if WITH_GUI == 1 -#include +#include #endif class PointClouds diff --git a/core/include/pose_graph_loop_closure.h b/core/include/Core/pose_graph_loop_closure.h similarity index 94% rename from core/include/pose_graph_loop_closure.h rename to core/include/Core/pose_graph_loop_closure.h index 8adcd622..2d60089a 100644 --- a/core/include/pose_graph_loop_closure.h +++ b/core/include/Core/pose_graph_loop_closure.h @@ -1,9 +1,9 @@ #pragma once -#include -#include -#include -#include +#include +#include +#include +#include class PoseGraphLoopClosure { diff --git a/core/include/pose_graph_slam.h b/core/include/Core/pose_graph_slam.h similarity index 98% rename from core/include/pose_graph_slam.h rename to core/include/Core/pose_graph_slam.h index 5f9d5bed..ad4c58c4 100644 --- a/core/include/pose_graph_slam.h +++ b/core/include/Core/pose_graph_slam.h @@ -1,7 +1,7 @@ #pragma once -#include -#include +#include +#include class PoseGraphSLAM { diff --git a/core/include/registration_plane_feature.h b/core/include/Core/registration_plane_feature.h similarity index 99% rename from core/include/registration_plane_feature.h rename to core/include/Core/registration_plane_feature.h index e40c3a2e..f76ffa60 100644 --- a/core/include/registration_plane_feature.h +++ b/core/include/Core/registration_plane_feature.h @@ -1,6 +1,6 @@ #pragma once -#include +#include class RegistrationPlaneFeature { diff --git a/core/include/session.h b/core/include/Core/session.h similarity index 85% rename from core/include/session.h rename to core/include/Core/session.h index 763d2c78..57f13717 100644 --- a/core/include/session.h +++ b/core/include/Core/session.h @@ -1,16 +1,17 @@ #pragma once -#include +#include + #include #include #if WITH_GUI == 1 -#include -#include -#include +#include +#include +#include #else -#include +#include #endif class Session diff --git a/core/include/structures.h b/core/include/Core/structures.h similarity index 100% rename from core/include/structures.h rename to core/include/Core/structures.h diff --git a/core/include/system_info.hpp b/core/include/Core/system_info.hpp similarity index 100% rename from core/include/system_info.hpp rename to core/include/Core/system_info.hpp diff --git a/core/include/transformations.h b/core/include/Core/transformations.h similarity index 100% rename from core/include/transformations.h rename to core/include/Core/transformations.h diff --git a/core/include/utils.hpp b/core/include/Core/utils.hpp similarity index 97% rename from core/include/utils.hpp rename to core/include/Core/utils.hpp index 853acf6a..0835a52b 100644 --- a/core/include/utils.hpp +++ b/core/include/Core/utils.hpp @@ -3,11 +3,13 @@ #pragma once -#include +#include +#include +#include + #include -#include -#include -#include + +#include /////////////////////////////////////////////////////////////////////////////////// diff --git a/core/src/color_las_loader.cpp b/core/src/color_las_loader.cpp index 3edcd8ba..d74fafae 100644 --- a/core/src/color_las_loader.cpp +++ b/core/src/color_las_loader.cpp @@ -1,6 +1,6 @@ #include -#include "color_las_loader.h" +#include "Core/color_las_loader.h" #include diff --git a/core/src/control_points.cpp b/core/src/control_points.cpp index d46532dc..eef1a18c 100644 --- a/core/src/control_points.cpp +++ b/core/src/control_points.cpp @@ -1,6 +1,6 @@ #include -#include +#include #include diff --git a/core/src/gnss.cpp b/core/src/gnss.cpp index 8e0d97ac..6b94f70e 100644 --- a/core/src/gnss.cpp +++ b/core/src/gnss.cpp @@ -1,8 +1,9 @@ #include +#include +#include + #include -#include -#include #include #if WITH_GUI == 1 diff --git a/core/src/ground_control_points.cpp b/core/src/ground_control_points.cpp index 02fc2519..2e530c4a 100644 --- a/core/src/ground_control_points.cpp +++ b/core/src/ground_control_points.cpp @@ -1,7 +1,9 @@ #include -#include +#include + #include + #if WITH_GUI == 1 #include #include diff --git a/core/src/hash_utils.cpp b/core/src/hash_utils.cpp index de550736..3ac5dfde 100644 --- a/core/src/hash_utils.cpp +++ b/core/src/hash_utils.cpp @@ -1,6 +1,6 @@ #include -#include +#include uint64_t get_index_2d(const int16_t x, const int16_t y) { diff --git a/core/src/icp.cpp b/core/src/icp.cpp index ddd3509c..11c8ac34 100644 --- a/core/src/icp.cpp +++ b/core/src/icp.cpp @@ -1,13 +1,12 @@ #include -#include +#include +#include +#include #include #include -#include -#include - std::vector ICP::get_jobs(uint64_t size, int num_threads) { int hc = size / num_threads; diff --git a/core/src/manual_pose_graph_loop_closure.cpp b/core/src/manual_pose_graph_loop_closure.cpp index 912e77f5..c5c9f283 100644 --- a/core/src/manual_pose_graph_loop_closure.cpp +++ b/core/src/manual_pose_graph_loop_closure.cpp @@ -1,10 +1,15 @@ #include #if WITH_GUI == 1 -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include #include @@ -15,17 +20,8 @@ #include #include -#include -#include - #include -#include - -#include "export_laz.h" - -#include - void ManualPoseGraphLoopClosure::Gui( PointClouds& point_clouds_container, int& index_loop_closure_source, diff --git a/core/src/ndt.cpp b/core/src/ndt.cpp index 36d360a7..3cca056a 100644 --- a/core/src/ndt.cpp +++ b/core/src/ndt.cpp @@ -1,11 +1,9 @@ #include -#include -#include - -#include - -#include +#include +#include +#include +#include #include #include diff --git a/core/src/nmea.cpp b/core/src/nmea.cpp index 4f10ae3e..85b1df93 100644 --- a/core/src/nmea.cpp +++ b/core/src/nmea.cpp @@ -1,6 +1,6 @@ #include -#include "nmea.h" +#include namespace hd_mapping::nmea { diff --git a/core/src/observation_picking.cpp b/core/src/observation_picking.cpp index e4034f5f..d59550b0 100644 --- a/core/src/observation_picking.cpp +++ b/core/src/observation_picking.cpp @@ -1,8 +1,8 @@ #include -#include -#include +#include +#include #include // void renderBitmapString(float x, float y, float z, char* string) { diff --git a/core/src/optimization_point_to_point_source_to_target.cpp b/core/src/optimization_point_to_point_source_to_target.cpp index 4b536c9e..8aad8bb0 100644 --- a/core/src/optimization_point_to_point_source_to_target.cpp +++ b/core/src/optimization_point_to_point_source_to_target.cpp @@ -1,19 +1,16 @@ #include -#include - -#include -#include - -#include -#include - -#include -#include +#include +#include +#include #include #include #include +#include +#include +#include +#include Eigen::Matrix get_delta_point_to_point_tait_bryan( ICP::PoseConvention pose_convention, Eigen::Affine3d m_pose_wc, Eigen::Vector3d p_s, Eigen::Vector3d p_t) diff --git a/core/src/optimize_distance_point_to_plane_source_to_target.cpp b/core/src/optimize_distance_point_to_plane_source_to_target.cpp index 4b8664fd..e22311c7 100644 --- a/core/src/optimize_distance_point_to_plane_source_to_target.cpp +++ b/core/src/optimize_distance_point_to_plane_source_to_target.cpp @@ -1,18 +1,16 @@ #include -#include -#include -#include - -#include -#include - -#include -#include +#include +#include +#include #include #include #include +#include +#include +#include +#include Eigen::Matrix get_delta_distance_point_to_plane_tait_bryan( RegistrationPlaneFeature::PoseConvention pose_convention, diff --git a/core/src/optimize_plane_to_plane_source_to_target.cpp b/core/src/optimize_plane_to_plane_source_to_target.cpp index f89b0bec..1d9ddd6f 100644 --- a/core/src/optimize_plane_to_plane_source_to_target.cpp +++ b/core/src/optimize_plane_to_plane_source_to_target.cpp @@ -1,20 +1,17 @@ #include -#include -#include - -#include -#include - -#include -#include - -#include -#include +#include +#include +#include +#include #include #include #include +#include +#include +#include +#include Eigen::Matrix get_plane_to_plane_source_to_target_tait_bryan( RegistrationPlaneFeature::PoseConvention pose_convention, diff --git a/core/src/optimize_point_to_plane_source_to_target.cpp b/core/src/optimize_point_to_plane_source_to_target.cpp index 1232bf8d..237381df 100644 --- a/core/src/optimize_point_to_plane_source_to_target.cpp +++ b/core/src/optimize_point_to_plane_source_to_target.cpp @@ -1,18 +1,16 @@ #include -#include -#include -#include - -#include -#include - -#include -#include +#include +#include +#include #include #include #include +#include +#include +#include +#include Eigen::Matrix get_delta_point_to_plane_tait_bryan( RegistrationPlaneFeature::PoseConvention pose_convention, diff --git a/core/src/optimize_point_to_projection_onto_plane_source_to_target.cpp b/core/src/optimize_point_to_projection_onto_plane_source_to_target.cpp index 91933852..d233f3e7 100644 --- a/core/src/optimize_point_to_projection_onto_plane_source_to_target.cpp +++ b/core/src/optimize_point_to_projection_onto_plane_source_to_target.cpp @@ -1,23 +1,17 @@ #include -#include -#include - -#include -#include -// #include -#include -#include - -#include -#include +#include +#include +#include +#include #include #include #include - -// #include -// #include +#include +#include +#include +#include Eigen::Matrix get_delta_point_to_projection_onto_plane_tait_bryan( RegistrationPlaneFeature::PoseConvention pose_convention, diff --git a/core/src/pair_wise_iterative_closest_point.cpp b/core/src/pair_wise_iterative_closest_point.cpp index f1494d66..9c1371da 100644 --- a/core/src/pair_wise_iterative_closest_point.cpp +++ b/core/src/pair_wise_iterative_closest_point.cpp @@ -1,10 +1,11 @@ #include -#include -#include +#include +#include +#include +#include + #include -#include -#include inline void point_to_point_source_to_target_tait_bryan_wc_AtPA_simplified_4( Eigen::Matrix& AtPA, @@ -295,7 +296,13 @@ bool PairWiseICP::compute( if (multithread) { - std::for_each(std::execution::par_unseq, std::begin(source), std::end(source), hessian_fun); + std::for_each( +#if USE_EXECUTION_PAR_UNSEQ + std::execution::par_unseq, +#endif + std::begin(source), + std::end(source), + hessian_fun); } else { @@ -502,7 +509,13 @@ bool PairWiseICP::compute_fast( if (multithread) { - std::for_each(std::execution::par_unseq, std::begin(source), std::end(source), hessian_fun); + std::for_each( +#if USE_EXECUTION_PAR_UNSEQ + std::execution::par_unseq, +#endif + std::begin(source), + std::end(source), + hessian_fun); } else { diff --git a/core/src/pfd_wrapper.cpp b/core/src/pfd_wrapper.cpp index 0b0da44c..c34357d0 100644 --- a/core/src/pfd_wrapper.cpp +++ b/core/src/pfd_wrapper.cpp @@ -1,6 +1,7 @@ #include -#include +#include + #include namespace mandeye::fd diff --git a/core/src/point_cloud.cpp b/core/src/point_cloud.cpp index da5be209..cb7327c2 100644 --- a/core/src/point_cloud.cpp +++ b/core/src/point_cloud.cpp @@ -1,7 +1,7 @@ #include -#include -#include +#include +#include #include @@ -317,6 +317,7 @@ bool PointCloud::build_rgd() std::vector threads; + // TODO(mwlasiuk) : uint64 -> uint32 conversion warning for (size_t i = 0; i < jobs.size(); i++) { threads.push_back(std::thread(build_rgd_init_job, i, &jobs[i], &buckets)); diff --git a/core/src/point_clouds.cpp b/core/src/point_clouds.cpp index ab48009a..8841d6c6 100644 --- a/core/src/point_clouds.cpp +++ b/core/src/point_clouds.cpp @@ -1,9 +1,9 @@ #include -#include -#include -#include +#include +#include +#include #include inline void split(std::string& str, char delim, std::vector& out) @@ -1259,7 +1259,9 @@ bool PointClouds::load_whu_tls( point_clouds.resize(point_clouds_nodata.size()); std::transform( +#if USE_EXECUTION_PAR_UNSEQ std::execution::par_unseq, +#endif std::begin(point_clouds_nodata), std::end(point_clouds_nodata), std::begin(point_clouds), diff --git a/core/src/pose_graph_loop_closure.cpp b/core/src/pose_graph_loop_closure.cpp index 1d80f7c6..ce902dd3 100644 --- a/core/src/pose_graph_loop_closure.cpp +++ b/core/src/pose_graph_loop_closure.cpp @@ -1,13 +1,14 @@ #include #include -#include -#include -#include -#include -#include -#include -#include + +#include +#include +#include +#include +#include +#include +#include #include #include diff --git a/core/src/pose_graph_slam.cpp b/core/src/pose_graph_slam.cpp index 12361548..baa533de 100644 --- a/core/src/pose_graph_slam.cpp +++ b/core/src/pose_graph_slam.cpp @@ -1,6 +1,11 @@ #include -#include +#include +#include +#include +#include +#include + #include #include #include @@ -8,11 +13,6 @@ #include #include -#include - -#include -#include - #ifdef WITH_PCL #include #include @@ -38,8 +38,6 @@ #include #endif -#include - std::random_device rd; std::mt19937 gen(rd()); diff --git a/core/src/registration_plane_feature.cpp b/core/src/registration_plane_feature.cpp index 215a3bf7..d819c736 100644 --- a/core/src/registration_plane_feature.cpp +++ b/core/src/registration_plane_feature.cpp @@ -1,10 +1,9 @@ #include -#include -#include - -#include -#include +#include +#include +#include +#include #include #include diff --git a/core/src/session.cpp b/core/src/session.cpp index 025282af..bbc2fe9f 100644 --- a/core/src/session.cpp +++ b/core/src/session.cpp @@ -1,8 +1,10 @@ #include -#include "../../shared/include/HDMapping/Version.hpp" +#include + #include -#include + +#include namespace fs = std::filesystem; diff --git a/core/src/utils.cpp b/core/src/utils.cpp index bbc6aaf4..e1f03265 100644 --- a/core/src/utils.cpp +++ b/core/src/utils.cpp @@ -15,7 +15,7 @@ #include #include -#include "utils.hpp" +#include #include diff --git a/core_hd_mapping/include/laz_wrapper.h b/core_hd_mapping/include/CoreHDMapping/laz_wrapper.h similarity index 85% rename from core_hd_mapping/include/laz_wrapper.h rename to core_hd_mapping/include/CoreHDMapping/laz_wrapper.h index 0ec66154..dead6210 100644 --- a/core_hd_mapping/include/laz_wrapper.h +++ b/core_hd_mapping/include/CoreHDMapping/laz_wrapper.h @@ -7,8 +7,10 @@ #include -#include -#include +#include + +// TODO(mwlasiuk) : cross includes ??? +#include class LazWrapper { diff --git a/core_hd_mapping/include/odo_with_gnss_fusion.h b/core_hd_mapping/include/CoreHDMapping/odo_with_gnss_fusion.h similarity index 95% rename from core_hd_mapping/include/odo_with_gnss_fusion.h rename to core_hd_mapping/include/CoreHDMapping/odo_with_gnss_fusion.h index f01520e8..4c2ea0d9 100644 --- a/core_hd_mapping/include/odo_with_gnss_fusion.h +++ b/core_hd_mapping/include/CoreHDMapping/odo_with_gnss_fusion.h @@ -9,7 +9,8 @@ #include -#include +// TODO(mwlasiuk) : cross includes ??? +#include class OdoWithGnssFusion { diff --git a/core_hd_mapping/include/project_settings.h b/core_hd_mapping/include/CoreHDMapping/project_settings.h similarity index 93% rename from core_hd_mapping/include/project_settings.h rename to core_hd_mapping/include/CoreHDMapping/project_settings.h index 54e100e6..78d0c8ba 100644 --- a/core_hd_mapping/include/project_settings.h +++ b/core_hd_mapping/include/CoreHDMapping/project_settings.h @@ -7,8 +7,10 @@ #include -#include -#include +#include + +// TODO(mwlasiuk) : cross includes ??? +#include class ProjectSettings { diff --git a/core_hd_mapping/include/roi_exporter.h b/core_hd_mapping/include/CoreHDMapping/roi_exporter.h similarity index 88% rename from core_hd_mapping/include/roi_exporter.h rename to core_hd_mapping/include/CoreHDMapping/roi_exporter.h index 51080f73..059fce22 100644 --- a/core_hd_mapping/include/roi_exporter.h +++ b/core_hd_mapping/include/CoreHDMapping/roi_exporter.h @@ -7,8 +7,10 @@ #include -#include -#include +#include + +// TODO(mwlasiuk) : cross includes ??? +#include class RoiExporter { diff --git a/core_hd_mapping/include/single_trajectory_viewer.h b/core_hd_mapping/include/CoreHDMapping/single_trajectory_viewer.h similarity index 92% rename from core_hd_mapping/include/single_trajectory_viewer.h rename to core_hd_mapping/include/CoreHDMapping/single_trajectory_viewer.h index d216a46e..c3684472 100644 --- a/core_hd_mapping/include/single_trajectory_viewer.h +++ b/core_hd_mapping/include/CoreHDMapping/single_trajectory_viewer.h @@ -7,8 +7,9 @@ #include -#include -#include +#include + +#include class SingleTrajectoryViewer { diff --git a/core_hd_mapping/src/laz_wrapper.cpp b/core_hd_mapping/src/laz_wrapper.cpp index cf7d65cd..684b4568 100644 --- a/core_hd_mapping/src/laz_wrapper.cpp +++ b/core_hd_mapping/src/laz_wrapper.cpp @@ -1,6 +1,6 @@ #include -#include +#include #include #include @@ -10,7 +10,7 @@ #include #include -#include +#include #include diff --git a/core_hd_mapping/src/odo_with_gnss_fusion.cpp b/core_hd_mapping/src/odo_with_gnss_fusion.cpp index 127c7c4b..92273459 100644 --- a/core_hd_mapping/src/odo_with_gnss_fusion.cpp +++ b/core_hd_mapping/src/odo_with_gnss_fusion.cpp @@ -1,14 +1,13 @@ #include -#include +#include #include #include -#include -#include - -#include +#include +#include +#include #include #include @@ -22,8 +21,7 @@ void OdoWithGnssFusion::imgui(CommonData& common_data) if (ImGui::Button("load GNSS trajectory")) { - std::string input_file_name = ""; - input_file_name = mandeye::fd::OpenFileDialogOneFile("Load GNSS trajectory", {}); + std::string input_file_name = mandeye::fd::OpenFileDialogOneFile("Load GNSS trajectory", {}); if (input_file_name.size() > 0) { diff --git a/core_hd_mapping/src/project_settings.cpp b/core_hd_mapping/src/project_settings.cpp index 70121caf..b4b3d94d 100644 --- a/core_hd_mapping/src/project_settings.cpp +++ b/core_hd_mapping/src/project_settings.cpp @@ -1,14 +1,14 @@ #include -#include +#include #include #include #include -#include -#include -#include +#include +#include +#include #include #include diff --git a/core_hd_mapping/src/roi_exporter.cpp b/core_hd_mapping/src/roi_exporter.cpp index e9c24019..fd89a1da 100644 --- a/core_hd_mapping/src/roi_exporter.cpp +++ b/core_hd_mapping/src/roi_exporter.cpp @@ -1,15 +1,15 @@ #include -#include +#include + +#include +#include +#include #include #include #include -#include -#include -#include - std::vector decimate(const std::vector& pc) { std::vector pc_out; diff --git a/core_hd_mapping/src/single_trajectory_viewer.cpp b/core_hd_mapping/src/single_trajectory_viewer.cpp index 9468e6b3..d716ea91 100644 --- a/core_hd_mapping/src/single_trajectory_viewer.cpp +++ b/core_hd_mapping/src/single_trajectory_viewer.cpp @@ -1,10 +1,10 @@ -#include - #include +#include +#include +#include + #include -#include -#include namespace fs = std::filesystem; diff --git a/pybind/core_binding.cpp b/pybind/core_binding.cpp index 72a4acaa..dbe5fdc2 100644 --- a/pybind/core_binding.cpp +++ b/pybind/core_binding.cpp @@ -1,10 +1,11 @@ -#include #include #include #include #include -#include -#include + +#include +#include +#include namespace py = pybind11; diff --git a/pybind/lidar_odometry_binding.cpp b/pybind/lidar_odometry_binding.cpp index 932b4b7b..fc1f581c 100644 --- a/pybind/lidar_odometry_binding.cpp +++ b/pybind/lidar_odometry_binding.cpp @@ -1,12 +1,14 @@ -#include -#include -#include #include #include #include #include -#include -#include + +#include +#include + +#include +#include +#include namespace py = pybind11; diff --git a/pybind/tls_registration_binding.cpp b/pybind/tls_registration_binding.cpp index 531a8cc1..82799066 100644 --- a/pybind/tls_registration_binding.cpp +++ b/pybind/tls_registration_binding.cpp @@ -2,12 +2,13 @@ #include #include -#include -#include +#include +#include +#include +#include +#include + #include -#include -#include -#include namespace py = pybind11;