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
697 changes: 328 additions & 369 deletions apps/lidar_odometry_step_1/lidar_odometry.cpp

Large diffs are not rendered by default.

25 changes: 5 additions & 20 deletions apps/lidar_odometry_step_1/lidar_odometry_gui.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,7 @@ static const std::vector<ShortcutEntry> appShortcuts = {
{"", "Ctrl+Q", ""},
{"", "R", ""},
{"", "Ctrl+R", ""},
{"", "Shift+R", ""},
{"", "S", ""},
{"", "Ctrl+S", ""},
{"", "Ctrl+Shift+S", ""},
Expand Down Expand Up @@ -125,6 +126,7 @@ static const std::vector<ShortcutEntry> appShortcuts = {
{"", "Right click + drag", "n"},
{"", "Scroll", ""},
{"", "Shift + scroll", ""},
{"", "Shift + drag", ""},
{"", "Ctrl + left click", ""},
{"", "Ctrl + right click", ""},
{"", "Ctrl + middle click", ""} };
Expand Down Expand Up @@ -638,9 +640,7 @@ void step2(const std::atomic<bool> &loPause)
{
double ts_failure = 0.0;
if (compute_step_2(worker_data, params, ts_failure, loProgress, loPause, full_debug_messages))
{
step_2_done = true;
}
else
{
for (size_t fileNo = 0; fileNo < csv_files.size(); fileNo++)
Expand All @@ -655,9 +655,7 @@ void step2(const std::atomic<bool> &loPause)
if (imu.size() > 0)
{
if (std::get<0>(imu[imu.size() - 1]).first > ts_failure)
{
break;
}
}
std::cout << "file: '" << imufn << "' [OK]" << std::endl;
}
Expand Down Expand Up @@ -1459,7 +1457,7 @@ void progress_window()
{
ImGui::Begin("Progress", nullptr, ImGuiWindowFlags_AlwaysAutoResize);

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

// Calculate elapsed time and ETA
auto currentTime = std::chrono::system_clock::now();
Expand Down Expand Up @@ -1507,9 +1505,8 @@ void progress_window()
if (!loPause)
{
if (ImGui::Button("Pause"))
{
loPause.store(true);
}

if (ImGui::IsItemHovered())
{
ImGui::BeginTooltip();
Expand All @@ -1521,9 +1518,7 @@ void progress_window()
else
{
if (ImGui::Button("Resume"))
{
loPause.store(false);
}
}
ImGui::SameLine();
ImGui::Text("Also check console for progress..");
Expand Down Expand Up @@ -1579,9 +1574,7 @@ void openData()
loThread.detach();
}
else //no data loaded
{
loRunning = false;
}
}

void step1(const std::string &folder,
Expand Down Expand Up @@ -1680,9 +1673,7 @@ void display()
if (show_covs)
{
for (const auto &b : params.buckets_indoor)
{
draw_ellipse(b.second.cov, b.second.mean, Eigen::Vector3f(0.0f, 0.0f, 1.0f), 3);
}
}

#if 0 // ToDo
Expand Down Expand Up @@ -1724,9 +1715,7 @@ void display()
glColor3f(1, 0, 0);
glBegin(GL_POINTS);
for (int i = 0; i < params.reference_points.size(); i += dec_reference_points)
{
glVertex3f(params.reference_points[i].point.x(), params.reference_points[i].point.y(), params.reference_points[i].point.z());
}
glEnd();
}

Expand Down Expand Up @@ -1762,9 +1751,7 @@ void display()
for (const auto &wd : worker_data)
{
for (const auto &it : wd.intermediate_trajectory)
{
glVertex3f(it(0, 3), it(1, 3), it(2, 3));
}
}
glEnd();
glPointSize(1);
Expand Down Expand Up @@ -1796,9 +1783,7 @@ void display()
glColor3f(1, 0, 0);
glBegin(GL_POINTS);
for (const auto &b : params.reference_buckets)
{
glVertex3f(b.second.mean.x(), b.second.mean.y(), b.second.mean.z());
}
glEnd();
}

Expand Down Expand Up @@ -2039,7 +2024,7 @@ void display()
toml_io.LoadParametersFromTomlFile(input_file_names[0], params);
std::cout << "Parameters loaded from: " << input_file_names[0] << std::endl;
}
catch (const std::exception &e)
catch (const std::exception& e)
{
std::cerr << "Error loading TOML file: " << e.what() << std::endl;
}
Expand Down
33 changes: 3 additions & 30 deletions apps/lidar_odometry_step_1/lidar_odometry_utils_optimizers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1510,13 +1510,9 @@ void optimize_lidar_odometry(std::vector<Point3Di> &intermediate_points,
};

if (multithread)
{
std::for_each(std::execution::par_unseq, std::begin(intermediate_points), std::end(intermediate_points), hessian_fun_indoor);
}
else
{
std::for_each(std::begin(intermediate_points), std::end(intermediate_points), hessian_fun_indoor);
}

if (ablation_study_use_hierarchical_rgd)
{
Expand All @@ -1525,42 +1521,34 @@ void optimize_lidar_odometry(std::vector<Point3Di> &intermediate_points,
const auto hessian_fun_outdoor = [&](const Point3Di &intermediate_points_i)
{
if (intermediate_points_i.point.norm() < 5.0 || intermediate_points_i.point.norm() > max_distance) // ToDo
{
return;
}

Eigen::Vector3d point_global = intermediate_trajectory[intermediate_points_i.index_pose] * intermediate_points_i.point;
auto index_of_bucket = get_rgd_index(point_global, b_outdoor);

auto bucket_it = buckets_outdoor.find(index_of_bucket);
// no bucket found
if (bucket_it == buckets_outdoor.end())
{
return;
}

auto &this_bucket = bucket_it->second;

const Eigen::Matrix3d &infm = this_bucket.cov.inverse();
const double threshold = 100000.0;

if ((infm.array() > threshold).any())
{
return;
}

if ((infm.array() < -threshold).any())
{
return;
}

if (ablation_study_use_view_point_and_normal_vectors)
{
// check nv
Eigen::Vector3d &nv = this_bucket.normal_vector;
Eigen::Vector3d viewport = intermediate_trajectory[intermediate_points_i.index_pose].translation();
if (nv.dot(viewport - this_bucket.mean) < 0)
{
return;
}
}

const Eigen::Affine3d &m_pose = intermediate_trajectory[intermediate_points_i.index_pose];
Expand Down Expand Up @@ -1617,32 +1605,23 @@ void optimize_lidar_odometry(std::vector<Point3Di> &intermediate_points,
};

if (multithread)
{
std::for_each(std::execution::par_unseq, std::begin(intermediate_points), std::end(intermediate_points), hessian_fun_outdoor);
}
else
{
std::for_each(std::begin(intermediate_points), std::end(intermediate_points), hessian_fun_outdoor);
}
}

std::vector<std::pair<int, int>> odo_edges;
for (size_t i = 1; i < intermediate_trajectory.size(); i++)
{
odo_edges.emplace_back(i - 1, i);
}

std::vector<TaitBryanPose> poses;
std::vector<TaitBryanPose> poses_desired;

for (size_t i = 0; i < intermediate_trajectory.size(); i++)
{
poses.push_back(pose_tait_bryan_from_affine_matrix(intermediate_trajectory[i]));
}

for (size_t i = 0; i < intermediate_trajectory_motion_model.size(); i++)
{
poses_desired.push_back(pose_tait_bryan_from_affine_matrix(intermediate_trajectory_motion_model[i]));
}

for (size_t i = 0; i < odo_edges.size(); i++)
{
Expand Down Expand Up @@ -1804,12 +1783,8 @@ void optimize_lidar_odometry(std::vector<Point3Di> &intermediate_points,
Eigen::SparseMatrix<double> x = solver.solve(AtPB);
std::vector<double> h_x;
for (int k = 0; k < x.outerSize(); ++k)
{
for (Eigen::SparseMatrix<double>::InnerIterator it(x, k); it; ++it)
{
h_x.push_back(it.value());
}
}

delta = 1000000.0;
if (h_x.size() == 6 * intermediate_trajectory.size())
Expand Down Expand Up @@ -1843,9 +1818,7 @@ void optimize_lidar_odometry(std::vector<Point3Di> &intermediate_points,
}
delta = 0.0;
for (int i = 0; i < h_x.size(); i++)
{
delta += sqrt(h_x[i] * h_x[i]);
}
}
return;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ std::vector<std::string> infoLines = {
};

//App specific shortcuts (using empty dummy until needed)
std::vector<ShortcutEntry> appShortcuts(78, { "", "", "" });
std::vector<ShortcutEntry> appShortcuts(80, { "", "", "" });

#define SAMPLE_PERIOD (1.0 / 200.0)
namespace fs = std::filesystem;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,7 @@ static const std::vector<ShortcutEntry> appShortcuts = {
{"", "Ctrl+Q", ""},
{"", "R", ""},
{"", "Ctrl+R", ""},
{"", "Shift+R", ""},
{"", "S", ""},
{"", "Ctrl+S", ""},
{"", "Ctrl+Shift+S", ""},
Expand Down Expand Up @@ -121,6 +122,7 @@ static const std::vector<ShortcutEntry> appShortcuts = {
{"", "Right click + drag", "n"},
{"", "Scroll", ""},
{"", "Shift + scroll", ""},
{"", "Shift + drag", ""},
{"", "Ctrl + left click", ""},
{"", "Ctrl + right click", ""},
{"", "Ctrl + middle click", ""}
Expand Down Expand Up @@ -151,6 +153,7 @@ int oldcolorScheme = 0;
bool usePose = false;

Session session;
bool session_loaded = false;

//built in console output redirection to imgui window
///////////////////////////////////////////////////////////////////////////////////
Expand Down Expand Up @@ -695,7 +698,7 @@ void openSession()
std::string newTitle = winTitle + " - " + truncPath(session_file_name);
glutSetWindowTitle(newTitle.c_str());

session.load(fs::path(session_file_name).string(), false, 0.0, 0.0, 0.0, false);
session_loaded = session.load(fs::path(session_file_name).string(), false, 0.0, 0.0, 0.0, false);
index_rendered_points_local = 0;

if (gl_useVBOs)
Expand Down Expand Up @@ -1255,7 +1258,41 @@ void mouse(int glut_button, int state, int x, int y)
if (!io.WantCaptureMouse)
{
if ((glut_button == GLUT_MIDDLE_BUTTON || glut_button == GLUT_RIGHT_BUTTON) && state == GLUT_DOWN && io.KeyCtrl)
setNewRotationCenter(x, y);
{
if (session_loaded)
{
const auto laser_beam = GetLaserBeam(x, y);
double min_distance = std::numeric_limits<double>::max();

for (int j = 0; j < session.point_clouds_container.point_clouds[index_rendered_points_local].points_local.size(); j++)
{
auto vp = session.point_clouds_container.point_clouds[index_rendered_points_local].points_local[j];

if (usePose == true)
vp = session.point_clouds_container.point_clouds[index_rendered_points_local].m_pose * vp;

double dist = distance_point_to_line(vp, laser_beam);

if (dist < min_distance && dist < 0.1)
{
min_distance = dist;

new_rotation_center.x() = vp.x();
new_rotation_center.y() = vp.y();
new_rotation_center.z() = vp.z();
}
}

new_rotate_x = rotate_x;
new_rotate_y = rotate_y;
new_translate_x = -new_rotation_center.x();
new_translate_y = -new_rotation_center.y();
new_translate_z = translate_z;
camera_transition_active = true;
}
else
setNewRotationCenter(x, y);
}

if (state == GLUT_DOWN)
mouse_buttons |= 1 << glut_button;
Expand Down
Loading