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
9 changes: 5 additions & 4 deletions apps/lidar_odometry_step_1/lidar_odometry_gui.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -843,7 +843,7 @@ void lidar_odometry_gui()
params.in_out_params_indoor.resolution_X = 0.01;
}
ImGui::SameLine();
ImGui::InputDouble("X", &params.in_out_params_outdoor.resolution_X, 0.0, 0.0, "%.3f");
ImGui::InputDouble("X##ndt", &params.in_out_params_outdoor.resolution_X, 0.0, 0.0, "%.3f");
if (ImGui::IsItemHovered())
ImGui::SetTooltip(xText);
if (params.in_out_params_outdoor.resolution_X < 0.01)
Expand All @@ -859,7 +859,7 @@ void lidar_odometry_gui()
params.in_out_params_indoor.resolution_Y = 0.01;
}
ImGui::SameLine();
ImGui::InputDouble("Y", &params.in_out_params_outdoor.resolution_Y, 0.0, 0.0, "%.3f");
ImGui::InputDouble("Y##ndt", &params.in_out_params_outdoor.resolution_Y, 0.0, 0.0, "%.3f");
if (ImGui::IsItemHovered())
ImGui::SetTooltip(yText);
if (params.in_out_params_outdoor.resolution_Y < 0.01)
Expand All @@ -875,7 +875,7 @@ void lidar_odometry_gui()
params.in_out_params_indoor.resolution_Z = 0.01;
}
ImGui::SameLine();
ImGui::InputDouble("Z", &params.in_out_params_outdoor.resolution_Z, 0.0, 0.0, "%.3f");
ImGui::InputDouble("Z##ndt", &params.in_out_params_outdoor.resolution_Z, 0.0, 0.0, "%.3f");
if (ImGui::IsItemHovered())
ImGui::SetTooltip(zText);
if (params.in_out_params_outdoor.resolution_Z < 0.01)
Expand Down Expand Up @@ -1450,8 +1450,9 @@ void lidar_odometry_gui()
}
}
}
ImGui::End();
}

ImGui::End();
}

void progress_window()
Expand Down
58 changes: 29 additions & 29 deletions apps/lidar_odometry_step_1/lidar_odometry_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,35 @@ unsigned long long int get_rgd_index(const Eigen::Vector3d p, const Eigen::Vecto
return get_index(x, y, z);
}

std::vector<Point3Di> decimate(const std::vector<Point3Di>& points, double bucket_x, double bucket_y, double bucket_z)
{
// std::cout << "points.size before decimation: " << points.size() << std::endl;
Eigen::Vector3d b(bucket_x, bucket_y, bucket_z);
std::vector<Point3Di> out;

std::vector<PointCloud::PointBucketIndexPair> ip;
ip.resize(points.size());
out.reserve(points.size());

for (int i = 0; i < points.size(); i++)
{
ip[i].index_of_point = i;
ip[i].index_of_bucket = get_rgd_index(points[i].point, b);
}
std::sort(ip.begin(), ip.end(), [](const PointCloud::PointBucketIndexPair& a, const PointCloud::PointBucketIndexPair& b)
{ return a.index_of_bucket < b.index_of_bucket; });

if (ip.size() != 0)
out.emplace_back(points[ip[0].index_of_point]);

for (int i = 1; i < ip.size(); i++)
if (ip[i - 1].index_of_bucket != ip[i].index_of_bucket)
out.emplace_back(points[ip[i].index_of_point]);

// std::cout << "points.size after decimation: " << out.size() << std::endl;
return out;
}

Eigen::Matrix4d getInterpolatedPose(const std::map<double, Eigen::Matrix4d> &trajectory, double query_time)
{

Expand Down Expand Up @@ -91,35 +120,6 @@ Eigen::Matrix4d getInterpolatedPose(const std::map<double, Eigen::Matrix4d> &tra
return ret;
}

std::vector<Point3Di> decimate(const std::vector<Point3Di> &points, double bucket_x, double bucket_y, double bucket_z)
{
// std::cout << "points.size before decimation: " << points.size() << std::endl;
Eigen::Vector3d b(bucket_x, bucket_y, bucket_z);
std::vector<Point3Di> out;

std::vector<PointCloud::PointBucketIndexPair> ip;
ip.resize(points.size());
out.reserve(points.size());

for (int i = 0; i < points.size(); i++)
{
ip[i].index_of_point = i;
ip[i].index_of_bucket = get_rgd_index(points[i].point, b);
}
std::sort(ip.begin(), ip.end(), [](const PointCloud::PointBucketIndexPair &a, const PointCloud::PointBucketIndexPair &b)
{ return a.index_of_bucket < b.index_of_bucket; });
for (int i = 1; i < ip.size(); i++)
{
// std::cout << ip[i].index_of_bucket << " ";
if (ip[i - 1].index_of_bucket != ip[i].index_of_bucket)
{
out.emplace_back(points[ip[i].index_of_point]);
}
}
// std::cout << "points.size after decimation: " << out.size() << std::endl;
return out;
}

void limit_covariance(Eigen::Matrix3d &io_cov)
{
return;
Expand Down
19 changes: 9 additions & 10 deletions apps/multi_session_registration/multi_session_registration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2850,7 +2850,6 @@ void project_gui()
}
}
}
//
}
}

Expand Down Expand Up @@ -2960,9 +2959,9 @@ void project_gui()
// }
}
}

ImGui::End();
}

ImGui::End();
}

void display()
Expand Down Expand Up @@ -3385,7 +3384,7 @@ void display()
{
if (ImGui::MenuItem("Open project", "Ctrl+O"))
openProject();
if (ImGui::MenuItem("Save project", "Ctrl+S", nullptr, sessions.size() > 0))
if (ImGui::MenuItem("Save project", "Ctrl+S", nullptr, project_settings.session_file_names.size() > 0))
saveProject();

ImGui::Separator();
Expand Down Expand Up @@ -3437,7 +3436,7 @@ void display()
ImGui::Separator();

ImGui::Text("(x,y,z,r00,r01,r02,r10,r11,r12,r20,r21,r22)");
if (ImGui::MenuItem("Save all as csv (timestamp Lidar)"))
if (ImGui::MenuItem("Save all as csv (timestamp Lidar)##1"))
{
for (size_t i = 0; i < project_settings.session_file_names.size(); ++i)
{
Expand Down Expand Up @@ -3502,7 +3501,7 @@ void display()

std::cout << "Finished saving all trajectories to CSV files." << std::endl;
}
if (ImGui::MenuItem("Save all as csv (timestamp Unix)"))
if (ImGui::MenuItem("Save all as csv (timestamp Unix)##1"))
{
for (size_t i = 0; i < project_settings.session_file_names.size(); ++i)
{
Expand Down Expand Up @@ -3557,7 +3556,7 @@ void display()
}
}
}
if (ImGui::MenuItem("Save all as csv (timestamp Lidar, Unix)"))
if (ImGui::MenuItem("Save all as csv (timestamp Lidar, Unix)##1"))
{
for (size_t i = 0; i < project_settings.session_file_names.size(); ++i)
{
Expand Down Expand Up @@ -3618,7 +3617,7 @@ void display()
ImGui::Separator();
ImGui::Text("(x,y,z,qx,qy,qz,qw)");

if (ImGui::MenuItem("Save all as csv (timestamp Lidar)"))
if (ImGui::MenuItem("Save all as csv (timestamp Lidar)##2"))
{
for (size_t i = 0; i < project_settings.session_file_names.size(); ++i)
{
Expand Down Expand Up @@ -3678,7 +3677,7 @@ void display()

std::cout << "Finished saving all trajectories to CSV files." << std::endl;
}
if (ImGui::MenuItem("Save all as csv (timestamp Unix)"))
if (ImGui::MenuItem("Save all as csv (timestamp Unix)##2"))
{
for (size_t i = 0; i < project_settings.session_file_names.size(); ++i)
{
Expand Down Expand Up @@ -3738,7 +3737,7 @@ void display()

std::cout << "Finished saving all trajectories to CSV files." << std::endl;
}
if (ImGui::MenuItem("Save all as csv (timestamp Lidar, Unix)"))
if (ImGui::MenuItem("Save all as csv (timestamp Lidar, Unix)##2"))
{
for (size_t i = 0; i < project_settings.session_file_names.size(); ++i)
{
Expand Down
Loading