Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
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
27 changes: 26 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,6 @@ set(THIRDPARTY_DIRECTORY ${REPOSITORY_DIRECTORY}/3rdparty)
set(THIRDPARTY_DIRECTORY_BINARY ${REPOSITORY_DIRECTORY}/3rdpartyBinary)
set(EXTERNAL_LIBRARIES_DIRECTORY ${REPOSITORY_DIRECTORY}/external)


# CPU Architecture optimization options
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)
Expand Down Expand Up @@ -464,6 +463,32 @@ add_subdirectory(apps/livox_mid_360_intrinsic_calibration)
add_subdirectory(apps/single_session_manual_coloring)
add_subdirectory(apps/concatenate_multi_livox)

include(cmake/disable_target_warnings.cmake)

if(NOT WIN32)
disable_target_warnings(laszip)
disable_target_warnings(laszip_api)
else()
disable_target_warnings(laszip3)
disable_target_warnings(laszip_api3)
endif()


if(NOT WIN32)
disable_target_warnings(tbb)
disable_target_warnings(tbbbind_2_5)
else()
disable_target_warnings(tbb)
endif()

disable_target_warnings(freeglut)
disable_target_warnings(freeglut_static)
disable_target_warnings(libglew_static)
disable_target_warnings(libglew_shared)
disable_target_warnings(spdlog)
disable_target_warnings(vqf)
disable_target_warnings(Fusion)

# CPack configuration
set(CPACK_PACKAGE_NAME "hd_mapping")
set(CPACK_PACKAGE_VERSION "${HDMAPPING_VERSION_MAJOR}.${HDMAPPING_VERSION_MINOR}.${HDMAPPING_VERSION_PATCH}")
Expand Down
2 changes: 1 addition & 1 deletion apps/console_tools/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ target_include_directories(
${EIGEN3_INCLUDE_DIR}
${LASZIP_INCLUDE_DIR}/LASzip/include)

target_link_libraries(multiply_timestamps_session_point_cloud_laz PRIVATE ${PLATFORM_MISCELLANEOUS_LIBS} ${PLATFORM_LASZIP_LIB} spdlog::spdlog)
target_link_libraries(multiply_timestamps_session_point_cloud_laz PRIVATE ${PLATFORM_MISCELLANEOUS_LIBS} ${PLATFORM_LASZIP_LIB} core spdlog::spdlog)

add_executable(multiply_timestamps_session_trajectory_csv multiply_timestamps_session_trajectory_csv.cpp)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,9 +21,12 @@

#include "toml_io.h"
#include <HDMapping/Version.hpp>

#include <chrono>
#include <ctime>
#include <mutex>
#include <set>

#include <spdlog/cfg/env.h>
#include <spdlog/spdlog.h>

Expand Down Expand Up @@ -272,7 +275,7 @@ std::string formatCompletionTime(double remainingSeconds)
return std::string(timeStr);
}

int get_index_3d(const set<int>& s, int k)
int get_index_3d(const std::set<int>& s, int k)
{
int index = 0;
for (auto u : s)
Expand Down Expand Up @@ -1451,7 +1454,7 @@ void progress_window()
{
ImGui::Begin("Progress", nullptr, ImGuiWindowFlags_AlwaysAutoResize);

ImGui::Text(("Working directory:\n'" + working_directory + "'").c_str());
ImGui::Text("Working directory: %s", working_directory.c_str());

// Calculate elapsed time and ETA
auto currentTime = std::chrono::system_clock::now();
Expand Down
4 changes: 2 additions & 2 deletions apps/lidar_odometry_step_1/lidar_odometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1036,7 +1036,7 @@ void filter_reference_buckets(LidarOdometryParams& params)

void save_trajectory_to_ascii(std::vector<WorkerData>& worker_data, std::string output_file_name)
{
ofstream file;
std::ofstream file;
file.open(output_file_name);
for (const auto& wd : worker_data)
{
Expand Down Expand Up @@ -1241,7 +1241,7 @@ void save_processing_results_json(const LidarOdometryParams& params, const fs::p
file << results.dump(4); // Pretty print with 4-space indentation
file.close();
std::cout << "Processing results saved to JSON file: " << json_path << std::endl;
std::cout << "Processing time: " << fixed << std::setprecision(2) << elapsed_seconds << " [s]" << std::endl;
std::cout << "Processing time: " << std::fixed << std::setprecision(2) << elapsed_seconds << " [s]" << std::endl;
}
else
{
Expand Down
1 change: 0 additions & 1 deletion apps/lidar_odometry_step_1/lidar_odometry.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
#include "lidar_odometry_utils.h"
#include "toml_io.h"
#include <HDMapping/Version.hpp>
#include <laszip/laszip_api.h>
#include <nlohmann/json.hpp>

#include <Core/export_laz.h>
Expand Down
8 changes: 6 additions & 2 deletions apps/lidar_odometry_step_1/lidar_odometry_gui.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,9 +21,12 @@

#include "toml_io.h"
#include <HDMapping/Version.hpp>

#include <chrono>
#include <ctime>
#include <mutex>
#include <set>

#include <spdlog/cfg/env.h>
#include <spdlog/spdlog.h>

Expand Down Expand Up @@ -303,7 +306,8 @@ std::vector<std::vector<Point3Di>> get_batches_of_points(std::string laz_file, i
}
#endif

int get_index_3d(const set<int>& s, int k)
// TODO(m.wlasiuk) : unify (multiple declarations ...)
int get_index_3d(const std::set<int>& s, int k)
{
int index = 0;
for (auto u : s)
Expand Down Expand Up @@ -1684,7 +1688,7 @@ void progress_window()
{
ImGui::Begin("Progress", nullptr, ImGuiWindowFlags_AlwaysAutoResize);

ImGui::Text(("Working directory:\n'" + working_directory + "'").c_str());
ImGui::Text("Working directory: %s", working_directory.c_str());

// Calculate elapsed time and ETA
auto currentTime = std::chrono::system_clock::now();
Expand Down
2 changes: 2 additions & 0 deletions apps/lidar_odometry_step_1/lidar_odometry_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,8 @@

#include <Core/hash_utils.h>

#include <laszip/laszip_api.h>

#include <spdlog/spdlog.h>

namespace fs = std::filesystem;
Expand Down
1 change: 0 additions & 1 deletion apps/lidar_odometry_step_1/lidar_odometry_utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,6 @@

#include <Eigen/Dense>
#include <common/include/cauchy.h>
#include <laszip/laszip_api.h>
#include <nlohmann/json.hpp>
#include <vqf.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,8 @@
#include <filesystem>
#include <mutex>

#include <laszip/laszip_api.h>

#include <spdlog/spdlog.h>

#define SAMPLE_PERIOD (1.0 / 200.0)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@
#include <glm/glm.hpp>
#include <glm/gtc/matrix_transform.hpp>

#include <laszip/laszip_api.h>

#include <spdlog/spdlog.h>

#include <Eigen/Eigen>
Expand Down
6 changes: 3 additions & 3 deletions apps/mandeye_raw_data_viewer/mandeye_raw_data_viewer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1265,7 +1265,7 @@ void imu_data_gui()
output_file_name = mandeye::fd::SaveFileDialog("Save IMU data", {}, "");
spdlog::info("file to save: '{}'", output_file_name);

ofstream file;
std::ofstream file;
file.open(output_file_name);
file << std::setprecision(20);
for (size_t i = 0; i < imu_data_plot.timestampLidar.size(); i++)
Expand Down Expand Up @@ -1800,7 +1800,7 @@ void display()
{
ImGui::BeginTooltip();
std::string fn = laz_files[indexes_to_filename[index_rendered_points_local]];
ImGui::Text(fn.c_str());
ImGui::Text("%s", fn.c_str());
ImGui::EndTooltip();
}
ImGui::SameLine();
Expand All @@ -1809,7 +1809,7 @@ void display()
{
ImGui::BeginTooltip();
std::string fn = laz_files[indexes_to_filename[index_rendered_points_local]];
ImGui::Text(fn.c_str());
ImGui::Text("%s", fn.c_str());
ImGui::EndTooltip();
}
ImGui::PopItemWidth();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -756,15 +756,15 @@ void openSession()
void session_gui()
{
ImGui::Text("File name:");
ImGui::Text(session.session_file_name.c_str());
ImGui::Text("%s", session.session_file_name.c_str());
ImGui::Text("Working directory:");
ImGui::Text(session.working_directory.c_str());
ImGui::Text("%s", session.working_directory.c_str());

ImGui::Separator();

ImGui::Text("Is ground truth: %s", session.is_ground_truth ? "yes" : "no");
ImGui::Text("Number of clouds: %zu", session.point_clouds_container.point_clouds.size());
ImGui::Text("Number of points: %zu", session_total_number_of_points);
ImGui::Text("Number of points: %d", session_total_number_of_points);

ImGui::Separator();

Expand Down Expand Up @@ -848,9 +848,9 @@ void session_gui()
void index_gui()
{
ImGui::Text("File name:");
ImGui::Text(session.point_clouds_container.point_clouds[index_rendered_points_local].file_name.c_str());
ImGui::Text("%s", session.point_clouds_container.point_clouds[index_rendered_points_local].file_name.c_str());

ImGui::Text("Current index: %zu / %zu", index_rendered_points_local, session.point_clouds_container.point_clouds.size());
ImGui::Text("Current index: %d / %zu", index_rendered_points_local, session.point_clouds_container.point_clouds.size());

ImGui::Separator();

Expand Down Expand Up @@ -1319,7 +1319,7 @@ void display()
if (ImGui::IsItemHovered())
{
ImGui::BeginTooltip();
ImGui::Text(session.point_clouds_container.point_clouds[index_rendered_points_local].file_name.c_str());
ImGui::Text("%s", session.point_clouds_container.point_clouds[index_rendered_points_local].file_name.c_str());
double ts = (session.point_clouds_container.point_clouds[index_rendered_points_local].timestamps[0] -
session.point_clouds_container.point_clouds[0].timestamps[0]) /
1e9;
Expand All @@ -1333,7 +1333,7 @@ void display()
if (ImGui::IsItemHovered())
{
ImGui::BeginTooltip();
ImGui::Text(session.point_clouds_container.point_clouds[index_rendered_points_local].file_name.c_str());
ImGui::Text("%s", session.point_clouds_container.point_clouds[index_rendered_points_local].file_name.c_str());
double ts = (session.point_clouds_container.point_clouds[index_rendered_points_local].timestamps[0] -
session.point_clouds_container.point_clouds[0].timestamps[0]) /
1e9;
Expand Down
6 changes: 3 additions & 3 deletions apps/manual_color/manual_color.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -637,8 +637,8 @@ void TimeStampCount()
}

ImGui::Text("Packed uint32_t: %u", packedValue);
ImGui::Text("Decoded timestamp: %llu", decodedValue);
ImGui::Text("Timestamp: %llu", fullTimestamp);
ImGui::Text("Decoded timestamp: %zu", decodedValue);
ImGui::Text("Timestamp: %zu", fullTimestamp);
double timestampSeconds = static_cast<double>(fullTimestamp) / 1'000'000'000.0;
ImGui::Text("Timestamp (formatted): %.6f", timestampSeconds);

Expand Down Expand Up @@ -1264,7 +1264,7 @@ void display()
{
auto index = std::distance(SystemData::pointPickedImage.begin(), it);
const auto& p = *it;
ImGui::Text("%d : %.1f,%.1f", index, p.x, p.y);
ImGui::Text("%d : %.1f,%.1f", (int)index, p.x, p.y);
ImGui::SameLine();
const auto label = std::string("-##2s") + std::to_string(index);
if (ImGui::Button(label.c_str()))
Expand Down
14 changes: 7 additions & 7 deletions apps/multi_session_registration/multi_session_registration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -400,7 +400,7 @@ void loop_closure_gui()
}

std::string number_active_edges = "number_edges: " + std::to_string(edges.size());
ImGui::Text(number_active_edges.c_str());
ImGui::Text("%s", number_active_edges.c_str());
if (edges.size() > 0)
{
ImGui::Checkbox("manipulate_active_edge", &manipulate_active_edge);
Expand Down Expand Up @@ -437,13 +437,13 @@ void loop_closure_gui()
}

std::string txt = "index_session_from: " + std::to_string(edges[index_active_edge].index_session_from);
ImGui::Text(txt.c_str());
ImGui::Text("%s", txt.c_str());
txt = "index_session_to: " + std::to_string(edges[index_active_edge].index_session_to);
ImGui::Text(txt.c_str());
ImGui::Text("%s", txt.c_str());
txt = "index_from: " + std::to_string(edges[index_active_edge].index_from);
ImGui::Text(txt.c_str());
ImGui::Text("%s", txt.c_str());
txt = "index_to: " + std::to_string(edges[index_active_edge].index_to);
ImGui::Text(txt.c_str());
ImGui::Text("%s", txt.c_str());

if (remove_edge_index != -1)
{
Expand Down Expand Up @@ -2309,9 +2309,9 @@ void settings_gui()

for (size_t i = 0; i < project_settings.session_file_names.size(); i++)
{
ImGui::Text(truncPath(project_settings.session_file_names[i]).c_str());
ImGui::Text("%s", truncPath(project_settings.session_file_names[i]).c_str());
if (ImGui::IsItemHovered())
ImGui::SetTooltip(project_settings.session_file_names[i].c_str());
ImGui::SetTooltip("%s", project_settings.session_file_names[i].c_str());

if (project_settings.session_file_names.size() == sessions.size())
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -795,13 +795,7 @@ void pose_graph_slam_gui()
tls_registration.pose_graph_slam.ndt_bucket_size[0] = tls_registration.ndt.bucket_size[0];
tls_registration.pose_graph_slam.ndt_bucket_size[1] = tls_registration.ndt.bucket_size[1];
tls_registration.pose_graph_slam.ndt_bucket_size[2] = tls_registration.ndt.bucket_size[2];
// double rms_initial = 0.0;
// double rms_final = 0.0;
// double mui = 0.0;
tls_registration.pose_graph_slam.optimize(session.point_clouds_container);
// pose_graph_slam.optimize(point_clouds_container, rms_initial, rms_final, mui);
// spdlog::info("mean uncertainty impact: " << mui << " rms_initial: " << rms_initial << " rms_final: " << rms_final <<
// std::endl;
}

#if WITH_GTSAM
Expand All @@ -816,8 +810,6 @@ void pose_graph_slam_gui()
double rms_final = 0.0;
double mui = 0.0;
tls_registration.pose_graph_slam.optimize_with_GTSAM(session.point_clouds_container);
// spdlog::info("mean uncertainty impact: " << mui << " rms_initial: " << rms_initial << " rms_final: " << rms_final <<
// std::endl;
}
#endif

Expand Down Expand Up @@ -893,7 +885,7 @@ void observation_picking_gui()
}
ImGui::EndDisabled();

ImGui::Text((std::string("Number of observations: ") + std::to_string(observation_picking.observations.size())).c_str());
ImGui::Text("Number of observations: %zu", observation_picking.observations.size());

if (ImGui::Button("Load observations"))
{
Expand Down Expand Up @@ -934,7 +926,7 @@ void observation_picking_gui()
observation_picking.export_observation(output_file_name);
}

ImGui::Text((std::string("Loaded observations from file: '") + observations_file_name + std::string("'")).c_str());
ImGui::Text("Loaded observations from file: %s", observations_file_name.c_str());

if (ImGui::Button("Compute RMS (xy)"))
{
Expand Down Expand Up @@ -1829,7 +1821,7 @@ void settings_gui()
ImGui::Begin("Settings", &is_settings_gui);
{
std::string wd = "Working directory: '" + session.working_directory + "'";
ImGui::Text(wd.c_str());
ImGui::Text("%s", wd.c_str());

ImGui::NewLine();

Expand Down Expand Up @@ -1999,7 +1991,7 @@ void settings_gui()
}
}
ImGui::SameLine();
ImGui::Text(session.point_clouds_container.initial_poses_file_name.c_str());
ImGui::Text("%s", session.point_clouds_container.initial_poses_file_name.c_str());

if (ImGui::Button("Update poses from RESSO file"))
{
Expand Down Expand Up @@ -2047,7 +2039,7 @@ void settings_gui()
}
}
ImGui::SameLine();
ImGui::Text(session.point_clouds_container.poses_file_name.c_str());
ImGui::Text("%s", session.point_clouds_container.poses_file_name.c_str());

ImGui::Separator();

Expand Down Expand Up @@ -3258,9 +3250,9 @@ void display()
{
ImGui::BeginTooltip();
ImGui::Text("Loaded session:");
ImGui::Text(std::string(session.session_file_name).c_str());
ImGui::Text("%s", session.session_file_name.c_str());
ImGui::Separator();
ImGui::Text("Total number of points: %zu", session_total_number_of_points);
ImGui::Text("Total number of points: %d", session_total_number_of_points);

if (ImGui::BeginTable("Dimensions", 4))
{
Expand Down
Loading
Loading