Skip to content
Merged
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
4 changes: 2 additions & 2 deletions apps/compare_trajectories/mandeye_compare_trajectories.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,8 @@

namespace fs = std::filesystem;

const unsigned int window_width = 800;
const unsigned int window_height = 600;
const uint32_t window_width = 800;
const uint32_t window_height = 600;
double camera_ortho_xy_view_zoom = 10;
double camera_ortho_xy_view_shift_x = 0.0;
double camera_ortho_xy_view_shift_y = 0.0;
Expand Down
4 changes: 2 additions & 2 deletions apps/hd_mapper/hd_mapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,8 @@ Eigen::Vector3d GLWidgetGetOGLPos(int x, int y, float picking_plane_height);
static bool show_demo_window = true;
static bool show_another_window = false;
// static ImVec4 clear_color = ImVec4(0.45f, 0.55f, 0.60f, 1.00f);
const unsigned int window_width = 800;
const unsigned int window_height = 600;
const uint32_t window_width = 800;
const uint32_t window_height = 600;
int mouse_old_x, mouse_old_y;
int mouse_buttons = 0;
bool gui_mouse_down{ false };
Expand Down
10 changes: 5 additions & 5 deletions apps/lidar_odometry_step_1/lidar_odometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -463,7 +463,7 @@ void calculate_trajectory(
}

bool compute_step_1(
std::vector<std::vector<Point3Di>>& pointsPerFile,
const std::vector<std::vector<Point3Di>>& pointsPerFile,
LidarOdometryParams& params,
Trajectory& trajectory,
std::vector<WorkerData>& worker_data,
Expand Down Expand Up @@ -681,7 +681,7 @@ bool compute_step_1(
return true;
}

void run_consistency(std::vector<WorkerData>& worker_data, LidarOdometryParams& params)
void run_consistency(std::vector<WorkerData>& worker_data, const LidarOdometryParams& params)
{
std::cout << "Point cloud consistency and trajectory smoothness START" << std::endl;
for (int i = 0; i < params.num_constistency_iter; i++)
Expand Down Expand Up @@ -1043,7 +1043,7 @@ void load_reference_point_clouds(const std::vector<std::string>& input_file_name
}

std::string save_results_automatic(
LidarOdometryParams& params, std::vector<WorkerData>& worker_data, std::string working_directory, double elapsed_seconds)
LidarOdometryParams& params, std::vector<WorkerData>& worker_data, const std::string& working_directory, double elapsed_seconds)
{
fs::path outwd = get_next_result_path(working_directory);
save_result(worker_data, params, outwd, elapsed_seconds);
Expand Down Expand Up @@ -1186,7 +1186,7 @@ void save_processing_results_json(const LidarOdometryParams& params, const fs::p
results["ndt_grid_indoor"]["resolution_X"] = params.in_out_params_indoor.resolution_X;
results["ndt_grid_indoor"]["resolution_Y"] = params.in_out_params_indoor.resolution_Y;
results["ndt_grid_indoor"]["resolution_Z"] = params.in_out_params_indoor.resolution_Z;
results["ndt_grid_indoor"]["number_of_buckets"] = static_cast<long long>(params.in_out_params_indoor.number_of_buckets);
results["ndt_grid_indoor"]["number_of_buckets"] = static_cast<int64_t>(params.in_out_params_indoor.number_of_buckets);

results["ndt_grid_outdoor"]["bounding_box_min_X"] = params.in_out_params_outdoor.bounding_box_min_X;
results["ndt_grid_outdoor"]["bounding_box_min_Y"] = params.in_out_params_outdoor.bounding_box_min_Y;
Expand All @@ -1197,7 +1197,7 @@ void save_processing_results_json(const LidarOdometryParams& params, const fs::p
results["ndt_grid_outdoor"]["resolution_X"] = params.in_out_params_outdoor.resolution_X;
results["ndt_grid_outdoor"]["resolution_Y"] = params.in_out_params_outdoor.resolution_Y;
results["ndt_grid_outdoor"]["resolution_Z"] = params.in_out_params_outdoor.resolution_Z;
results["ndt_grid_outdoor"]["number_of_buckets"] = static_cast<long long>(params.in_out_params_outdoor.number_of_buckets);
results["ndt_grid_outdoor"]["number_of_buckets"] = static_cast<int64_t>(params.in_out_params_outdoor.number_of_buckets);

// Motion model correction (complex structure)
results["motion_model_correction"]["om"] = params.motion_model_correction.om;
Expand Down
6 changes: 3 additions & 3 deletions apps/lidar_odometry_step_1/lidar_odometry.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,20 +32,20 @@ void calculate_trajectory(
bool debugMsg,
bool use_removie_imu_bias_from_first_stationary_scan);
bool compute_step_1(
std::vector<std::vector<Point3Di>>& pointsPerFile,
const std::vector<std::vector<Point3Di>>& pointsPerFile,
LidarOdometryParams& params,
Trajectory& trajectory,
std::vector<WorkerData>& worker_data,
const std::atomic<bool>& pause);
void run_consistency(std::vector<WorkerData>& worker_data, LidarOdometryParams& params);
void run_consistency(std::vector<WorkerData>& worker_data, const LidarOdometryParams& params);
void filter_reference_buckets(LidarOdometryParams& params);
void load_reference_point_clouds(const std::vector<std::string>& input_file_names, LidarOdometryParams& params);
void save_result(std::vector<WorkerData>& worker_data, LidarOdometryParams& params, fs::path outwd, double elapsed_seconds);
void save_parameters_toml(const LidarOdometryParams& params, const fs::path& outwd, double elapsed_seconds);
void save_processing_results_json(const LidarOdometryParams& params, const fs::path& outwd, double elapsed_seconds);
void save_trajectory_to_ascii(std::vector<WorkerData>& worker_data, std::string output_file_name);
std::string save_results_automatic(
LidarOdometryParams& params, std::vector<WorkerData>& worker_data, std::string working_directory, double elapsed_seconds);
LidarOdometryParams& params, std::vector<WorkerData>& worker_data, const std::string& working_directory, double elapsed_seconds);
std::vector<WorkerData> run_lidar_odometry(const std::string& input_dir, LidarOdometryParams& params);
// bool SaveParametersToTomlFile(const std::string &filepath, const LidarOdometryParams &params);
// bool LoadParametersFromTomlFile(const std::string &filepath, LidarOdometryParams &params);
6 changes: 3 additions & 3 deletions apps/lidar_odometry_step_1/lidar_odometry_gui.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -254,7 +254,7 @@ std::string formatCompletionTime(double remainingSeconds)
return "Calculating...";

auto now = std::chrono::system_clock::now();
auto estimatedCompletion = now + std::chrono::seconds(static_cast<long long>(remainingSeconds));
auto estimatedCompletion = now + std::chrono::seconds(static_cast<int64_t>(remainingSeconds));
auto completion_time_t = std::chrono::system_clock::to_time_t(estimatedCompletion);

// Format as HH:MM:SS - Cross-platform time formatting
Expand Down Expand Up @@ -299,7 +299,7 @@ std::vector<std::vector<Point3Di>> get_batches_of_points(std::string laz_file, i
}
#endif

int get_index(set<int> s, int k)
int get_index(const set<int>& s, int k)
{
int index = 0;
for (auto u : s)
Expand Down Expand Up @@ -349,7 +349,7 @@ void find_best_stretch(
}
///
std::vector<Eigen::Affine3d> best_trajectory = trajectory;
unsigned long long min_buckets = ULLONG_MAX;
uint64_t min_buckets = ULLONG_MAX;

for (double x = 0.0; x < 0.2; x += 0.0005)
{
Expand Down
25 changes: 14 additions & 11 deletions apps/lidar_odometry_step_1/lidar_odometry_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,15 +11,14 @@ namespace fs = std::filesystem;
// TODO(m.wlasiuk) : these 2 functions - core/utils

// this function provides unique index
unsigned long long int get_index(const int16_t x, const int16_t y, const int16_t z)
uint64_t get_index(const int16_t x, const int16_t y, const int16_t z)
{
return ((static_cast<unsigned long long int>(x) << 32) & (0x0000FFFF00000000ull)) |
((static_cast<unsigned long long int>(y) << 16) & (0x00000000FFFF0000ull)) |
((static_cast<unsigned long long int>(z) << 0) & (0x000000000000FFFFull));
return ((static_cast<uint64_t>(x) << 32) & (0x0000FFFF00000000ull)) | ((static_cast<uint64_t>(y) << 16) & (0x00000000FFFF0000ull)) |
((static_cast<uint64_t>(z) << 0) & (0x000000000000FFFFull));
}

// this function provides unique index for input point p and 3D space decomposition into buckets b
unsigned long long int get_rgd_index(const Eigen::Vector3d p, const Eigen::Vector3d b)
uint64_t get_rgd_index(const Eigen::Vector3d p, const Eigen::Vector3d b)
{
int16_t x = static_cast<int16_t>(p.x() / b.x());
int16_t y = static_cast<int16_t>(p.y() / b.y());
Expand Down Expand Up @@ -153,7 +152,11 @@ void limit_covariance(Eigen::Matrix3d& io_cov)
// std::cout << io_cov << std::endl;
}

void update_rgd(NDT::GridParameters& rgd_params, NDTBucketMapType& buckets, std::vector<Point3Di>& points_global, Eigen::Vector3d viewport)
void update_rgd(
const NDT::GridParameters& rgd_params,
NDTBucketMapType& buckets,
const std::vector<Point3Di>& points_global,
const Eigen::Vector3d& viewport)
{
Eigen::Vector3d b(rgd_params.resolution_X, rgd_params.resolution_Y, rgd_params.resolution_Z);

Expand Down Expand Up @@ -233,10 +236,10 @@ void update_rgd(NDT::GridParameters& rgd_params, NDTBucketMapType& buckets, std:
}

void update_rgd_spherical_coordinates(
NDT::GridParameters& rgd_params,
const NDT::GridParameters& rgd_params,
NDTBucketMapType& buckets,
std::vector<Point3Di>& points_global,
std::vector<Eigen::Vector3d>& points_global_spherical)
const std::vector<Point3Di>& points_global,
const std::vector<Eigen::Vector3d>& points_global_spherical)
{
Eigen::Vector3d b(rgd_params.resolution_X, rgd_params.resolution_Y, rgd_params.resolution_Z);

Expand Down Expand Up @@ -315,7 +318,7 @@ void update_rgd_spherical_coordinates(
}
}

bool save_poses(const std::string file_name, const std::vector<Eigen::Affine3d>& m_poses, const std::vector<std::string>& filenames)
bool save_poses(const std::string& file_name, const std::vector<Eigen::Affine3d>& m_poses, const std::vector<std::string>& filenames)
{
std::ofstream outfile;
outfile.open(file_name);
Expand Down Expand Up @@ -797,7 +800,7 @@ int MLvxCalib::GetImuIdToUse(const std::unordered_map<int, std::string>& idToSn,
return 0;
}

fs::path get_next_result_path(const std::string working_directory)
fs::path get_next_result_path(const std::string& working_directory)
{
std::regex pattern(R"(lio_result_(\d+))");
int max_number = -1;
Expand Down
24 changes: 12 additions & 12 deletions apps/lidar_odometry_step_1/lidar_odometry_utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -151,8 +151,8 @@ struct LidarOdometryParams
bool save_index_pose = false;
};

unsigned long long int get_index(const int16_t x, const int16_t y, const int16_t z);
unsigned long long int get_rgd_index(const Eigen::Vector3d p, const Eigen::Vector3d b);
uint64_t get_index(const int16_t x, const int16_t y, const int16_t z);
uint64_t get_rgd_index(const Eigen::Vector3d p, const Eigen::Vector3d b);

// this function finds interpolated pose between two poses according to query_time
Eigen::Matrix4d getInterpolatedPose(const std::map<double, Eigen::Matrix4d>& trajectory, double query_time);
Expand All @@ -162,16 +162,16 @@ std::vector<Point3Di> decimate(const std::vector<Point3Di>& points, double bucke

// this function updates each bucket (mean value, covariance) in regular grid decomposition
void update_rgd(
NDT::GridParameters& rgd_params,
const NDT::GridParameters& rgd_params,
NDTBucketMapType& buckets,
std::vector<Point3Di>& points_global,
Eigen::Vector3d viewport = Eigen::Vector3d(0, 0, 0));
const std::vector<Point3Di>& points_global,
const Eigen::Vector3d& viewport = Eigen::Vector3d(0, 0, 0));

void update_rgd_spherical_coordinates(
NDT::GridParameters& rgd_params,
const NDT::GridParameters& rgd_params,
NDTBucketMapType& buckets,
std::vector<Point3Di>& points_global,
std::vector<Eigen::Vector3d>& points_global_spherical);
const std::vector<Point3Di>& points_global,
const std::vector<Eigen::Vector3d>& points_global_spherical);

//! This function load inertial measurement unit data.
//! This function expects a file with the following format:
Expand Down Expand Up @@ -199,9 +199,9 @@ std::vector<Point3Di> load_point_cloud(
double filter_threshold_xy_outer,
const std::unordered_map<int, Eigen::Affine3d>& calibrations);

bool save_poses(const std::string file_name, const std::vector<Eigen::Affine3d>& m_poses, const std::vector<std::string>& filenames);
bool save_poses(const std::string& file_name, const std::vector<Eigen::Affine3d>& m_poses, const std::vector<std::string>& filenames);

fs::path get_next_result_path(const std::string working_directory);
fs::path get_next_result_path(const std::string& working_directory);

// this function performs main LiDAR odometry calculations
void optimize_lidar_odometry(
Expand Down Expand Up @@ -376,5 +376,5 @@ namespace MLvxCalib
int GetImuIdToUse(const std::unordered_map<int, std::string>& idToSn, const std::string& snToUse);
} // namespace MLvxCalib

void Consistency(std::vector<WorkerData>& worker_data, LidarOdometryParams& params);
void Consistency2(std::vector<WorkerData>& worker_data, LidarOdometryParams& params);
void Consistency(std::vector<WorkerData>& worker_data, const LidarOdometryParams& params);
void Consistency2(std::vector<WorkerData>& worker_data, const LidarOdometryParams& params);
32 changes: 16 additions & 16 deletions apps/lidar_odometry_step_1/lidar_odometry_utils_optimizers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,27 +35,27 @@ std::vector<std::pair<int, int>> nns(const std::vector<Point3Di>& points_global,

std::vector<std::pair<int, int>> nn;

std::vector<std::pair<unsigned long long int, unsigned int>> indexes;
std::vector<std::pair<uint64_t, uint32_t>> indexes;

for (int i = 0; i < points_global.size(); i++)
{
unsigned long long int index = get_rgd_index(points_global[i].point, search_radious);
uint64_t index = get_rgd_index(points_global[i].point, search_radious);
indexes.emplace_back(index, i);
}

std::sort(
indexes.begin(),
indexes.end(),
[](const std::pair<unsigned long long int, unsigned int>& a, const std::pair<unsigned long long int, unsigned int>& b)
[](const std::pair<uint64_t, uint32_t>& a, const std::pair<uint64_t, uint32_t>& b)
{
return a.first < b.first;
});

std::unordered_map<unsigned long long int, std::pair<unsigned int, unsigned int>> buckets;
std::unordered_map<uint64_t, std::pair<uint32_t, uint32_t>> buckets;

for (unsigned int i = 0; i < indexes.size(); i++)
for (uint32_t i = 0; i < indexes.size(); i++)
{
unsigned long long int index_of_bucket = indexes[i].first;
uint64_t index_of_bucket = indexes[i].first;
if (buckets.contains(index_of_bucket))
buckets[index_of_bucket].second = i;
else
Expand Down Expand Up @@ -85,7 +85,7 @@ std::vector<std::pair<int, int>> nns(const std::vector<Point3Di>& points_global,
for (double z = -search_radious.z(); z <= search_radious.z(); z += search_radious.z())
{
Eigen::Vector3d position_global = source.point + Eigen::Vector3d(x, y, z);
unsigned long long int index_of_bucket = get_rgd_index(position_global, search_radious);
uint64_t index_of_bucket = get_rgd_index(position_global, search_radious);

if (buckets.contains(index_of_bucket))
{
Expand Down Expand Up @@ -2420,8 +2420,8 @@ bool compute_step_2(
acc_distance = acc_distance_tmp;
std::cout << "please split data set into subsets" << std::endl;
ts_failure = worker_data[i].intermediate_trajectory_timestamps[0].first;
std::cout << "calculations canceled for TIMESTAMP: "
<< (long long int)worker_data[i].intermediate_trajectory_timestamps[0].first << std::endl;
std::cout << "calculations canceled for TIMESTAMP: " << (int64_t)worker_data[i].intermediate_trajectory_timestamps[0].first
<< std::endl;
return false;
}

Expand Down Expand Up @@ -2549,7 +2549,7 @@ void compute_step_2_fast_forward_motion(std::vector<WorkerData>& worker_data, Li
{
}

void Consistency(std::vector<WorkerData>& worker_data, LidarOdometryParams& params)
void Consistency(std::vector<WorkerData>& worker_data, const LidarOdometryParams& params)
{
std::vector<Eigen::Affine3d> trajectory;
std::vector<Eigen::Affine3d> trajectory_motion_model;
Expand Down Expand Up @@ -2916,7 +2916,7 @@ void Consistency(std::vector<WorkerData>& worker_data, LidarOdometryParams& para
worker_data[indexes[i].first].intermediate_trajectory[indexes[i].second] = trajectory[i];
}

void Consistency2(std::vector<WorkerData>& worker_data, LidarOdometryParams& params)
void Consistency2(std::vector<WorkerData>& worker_data, const LidarOdometryParams& params)
{
// global_tmp.clear();

Expand Down Expand Up @@ -3160,7 +3160,7 @@ void Consistency2(std::vector<WorkerData>& worker_data, LidarOdometryParams& par

// update_rgd2(params.in_out_params, buckets, points_global, trajectory[points_global[0].index_pose].translation());

std::vector<std::pair<unsigned long long int, unsigned int>> index_pairs;
std::vector<std::pair<uint64_t, uint32_t>> index_pairs;
for (int i = 0; i < points_global.size(); i++)
{
auto index_of_bucket = get_rgd_index(points_global[i].point, b);
Expand All @@ -3169,16 +3169,16 @@ void Consistency2(std::vector<WorkerData>& worker_data, LidarOdometryParams& par
std::sort(
index_pairs.begin(),
index_pairs.end(),
[](const std::pair<unsigned long long int, unsigned int>& a, const std::pair<unsigned long long int, unsigned int>& b)
[](const std::pair<uint64_t, uint32_t>& a, const std::pair<uint64_t, uint32_t>& b)
{
return a.first < b.first;
});

NDTBucketMapType2 buckets;

for (unsigned int i = 0; i < index_pairs.size(); i++)
for (uint32_t i = 0; i < index_pairs.size(); i++)
{
unsigned long long int index_of_bucket = index_pairs[i].first;
uint64_t index_of_bucket = index_pairs[i].first;
if (buckets.contains(index_of_bucket))
buckets[index_of_bucket].index_end_exclusive = i;
else
Expand All @@ -3192,7 +3192,7 @@ void Consistency2(std::vector<WorkerData>& worker_data, LidarOdometryParams& par
{
for (int i = b.second.index_begin_inclusive; i < b.second.index_end_exclusive; i++)
{
long long unsigned int index_point_segment = points_global[index_pairs[i].second].index_point;
uint64_t index_point_segment = points_global[index_pairs[i].second].index_point;

if (b.second.buckets.contains(index_point_segment))
b.second.buckets[index_point_segment].point_indexes.push_back(index_pairs[i].second);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,8 @@
#define SAMPLE_PERIOD (1.0 / 200.0)
namespace fs = std::filesystem;

const unsigned int window_width = 800;
const unsigned int window_height = 600;
const uint32_t window_width = 800;
const uint32_t window_height = 600;
double camera_ortho_xy_view_zoom = 10;
double camera_ortho_xy_view_shift_x = 0.0;
double camera_ortho_xy_view_shift_y = 0.0;
Expand Down
4 changes: 2 additions & 2 deletions apps/manual_color/manual_color.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,8 +98,8 @@ GLuint make_tex(const std::string& fn)
float rot = 0;
float width = 34;
float height = 71;
const unsigned int window_width = 500;
const unsigned int window_height = 400;
const uint32_t window_width = 500;
const uint32_t window_height = 400;
int mouse_old_x, mouse_old_y;
int mouse_buttons = 0;
float rotate_x = 0.0, rotate_y = 0.0;
Expand Down
Loading