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
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,6 @@

#include <ImGuizmo.h>

// #define GLEW_STATIC
// #include <GL/glew.h>
#include <GL/freeglut.h>
#include <portable-file-dialogs.h>

Expand Down
2 changes: 0 additions & 2 deletions apps/lidar_odometry_step_1/lidar_odometry_gui.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,6 @@

#include <ImGuizmo.h>

// #define GLEW_STATIC
// #include <GL/glew.h>
#include <GL/freeglut.h>
#include <portable-file-dialogs.h>

Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
#include "lidar_odometry_utils.h"
#include <UTL/profiler.hpp>
#include <imu_preintegration.h>
#include <spdlog/spdlog.h>
#include <spdlog/stopwatch.h>
#include <tbb/combinable.h>
Expand All @@ -9,6 +8,7 @@

#include <Core/export_laz.h>
#include <Core/hash_utils.h>
#include <Core/imu_preintegration.h>

const double DEG_TO_RAD = M_PI / 180.0f;
const double RAD_TO_DEG = 180.0f / M_PI;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,6 @@

#include <ImGuizmo.h>

// #define GLEW_STATIC
// #include <GL/glew.h>
#include <glm/glm.hpp>
#include <glm/gtc/matrix_transform.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,6 @@

#include <ImGuizmo.h>

// #define GLEW_STATIC
// #include <GL/glew.h>
#include <GL/freeglut.h>
#include <glm/glm.hpp>
#include <glm/gtc/matrix_transform.hpp>
Expand Down
23 changes: 5 additions & 18 deletions core/include/Core/control_points.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,6 @@

#include <string>
#include <vector>
#if WITH_GUI == 1
#include <GL/freeglut.h>
#endif

struct ControlPoint
{
Expand All @@ -27,32 +24,22 @@ struct ControlPoint
class ControlPoints
{
public:
ControlPoints()
{
;
};
~ControlPoints()
{
;
};
ControlPoints() = default;
~ControlPoints() = default;

bool is_imgui = false;
std::vector<ControlPoint> cps;

#if WITH_GUI == 1
bool picking_mode = false;
// int picking_mode_index_to_node_inner = -1;
// int picking_mode_index_to_node_outer = -1;
bool draw_uncertainty = false;
int index_picked_point = -1;
bool track_pose_with_camera = true;

int index_pose = 0;

// bool found_picked = false;
// ControlPoint picked_control_point;

void imgui(PointClouds& point_clouds_container, Eigen::Vector3f& rotation_center);
void imgui(PointClouds& point_clouds_container, const Eigen::Vector3f& rotation_center);
void render(const PointClouds& point_clouds_container, bool show_pc);
void draw_ellipse(const Eigen::Matrix3d& covar, Eigen::Vector3d& mean, Eigen::Vector3f color, float nstd = 1);
void draw_ellipse(const Eigen::Matrix3d& covar, const Eigen::Vector3d& mean, const Eigen::Vector3f& color, float nstd = 1);
#endif
};
16 changes: 3 additions & 13 deletions core/include/Core/ground_control_points.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,6 @@
#include <string>
#include <vector>

#if WITH_GUI == 1
#include <GL/freeglut.h>
#endif

struct GroundControlPoint
{
char name[64];
Expand All @@ -26,14 +22,8 @@ struct GroundControlPoint
class GroundControlPoints
{
public:
GroundControlPoints()
{
;
};
~GroundControlPoints()
{
;
};
GroundControlPoints() = default;
~GroundControlPoints() = default;

std::vector<GroundControlPoint> gpcs;
double default_lidar_height_above_ground = 0.15;
Expand All @@ -46,6 +36,6 @@ class GroundControlPoints

void imgui(PointClouds& point_clouds_container);
void render(const PointClouds& point_clouds_container);
void draw_ellipse(const Eigen::Matrix3d& covar, Eigen::Vector3d& mean, Eigen::Vector3f color, float nstd = 1);
void draw_ellipse(const Eigen::Matrix3d& covar, const Eigen::Vector3d& mean, const Eigen::Vector3f& color, float nstd = 1);
#endif
};
5 changes: 0 additions & 5 deletions core/include/Core/manual_pose_graph_loop_closure.h
Original file line number Diff line number Diff line change
@@ -1,11 +1,6 @@
#pragma once

#if WITH_GUI == 1

#include <GL/freeglut.h>

#include <imgui.h>

#include <Core/gnss.h>
#include <Core/observation_picking.h>
#include <Core/point_clouds.h>
Expand Down
95 changes: 2 additions & 93 deletions core/include/Core/observation_picking.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,6 @@
#include <Core/transformations.h>

#include <Eigen/Eigen>
#include <GL/freeglut.h>
#include <imgui.h>
#include <map>
#include <nlohmann/json.hpp>

Expand All @@ -31,96 +29,7 @@ class Intersection
float width_length_height[3];
std::vector<PointInsideIntersection> points;

void render()
{
TaitBryanPose pose;
pose.px = translation[0];
pose.py = translation[1];
pose.pz = translation[2];
pose.om = rotation[0];
pose.fi = rotation[1];
pose.ka = rotation[2];
Eigen::Affine3d m_pose = affine_matrix_from_pose_tait_bryan(pose);

float& x_length = width_length_height[0];
float& y_width = width_length_height[1];
float& z_height = width_length_height[2];

glColor3f(color[0], color[1], color[2]);

Eigen::Vector3d v000(-x_length * 0.5, -y_width * 0.5, -z_height * 0.5);
Eigen::Vector3d v100(x_length * 0.5, -y_width * 0.5, -z_height * 0.5);
Eigen::Vector3d v110(x_length * 0.5, y_width * 0.5, -z_height * 0.5);
Eigen::Vector3d v010(-x_length * 0.5, y_width * 0.5, -z_height * 0.5);

Eigen::Vector3d v001(-x_length * 0.5, -y_width * 0.5, z_height * 0.5);
Eigen::Vector3d v101(x_length * 0.5, -y_width * 0.5, z_height * 0.5);
Eigen::Vector3d v111(x_length * 0.5, y_width * 0.5, z_height * 0.5);
Eigen::Vector3d v011(-x_length * 0.5, y_width * 0.5, z_height * 0.5);

Eigen::Vector3d v000t = m_pose * v000;
Eigen::Vector3d v100t = m_pose * v100;
Eigen::Vector3d v110t = m_pose * v110;
Eigen::Vector3d v010t = m_pose * v010;

Eigen::Vector3d v001t = m_pose * v001;
Eigen::Vector3d v101t = m_pose * v101;
Eigen::Vector3d v111t = m_pose * v111;
Eigen::Vector3d v011t = m_pose * v011;

glBegin(GL_LINES);

glVertex3d(v000t.x(), v000t.y(), v000t.z());
glVertex3d(v100t.x(), v100t.y(), v100t.z());

glVertex3d(v100t.x(), v100t.y(), v100t.z());
glVertex3d(v110t.x(), v110t.y(), v110t.z());

glVertex3d(v110t.x(), v110t.y(), v110t.z());
glVertex3d(v010t.x(), v010t.y(), v010t.z());

glVertex3d(v010t.x(), v010t.y(), v010t.z());
glVertex3d(v000t.x(), v000t.y(), v000t.z());

glVertex3d(v001t.x(), v001t.y(), v001t.z());
glVertex3d(v101t.x(), v101t.y(), v101t.z());

glVertex3d(v101t.x(), v101t.y(), v101t.z());
glVertex3d(v111t.x(), v111t.y(), v111t.z());

glVertex3d(v111t.x(), v111t.y(), v111t.z());
glVertex3d(v011t.x(), v011t.y(), v011t.z());

glVertex3d(v011t.x(), v011t.y(), v011t.z());
glVertex3d(v001t.x(), v001t.y(), v001t.z());

glVertex3d(v000t.x(), v000t.y(), v000t.z());
glVertex3d(v001t.x(), v001t.y(), v001t.z());

glVertex3d(v100t.x(), v100t.y(), v100t.z());
glVertex3d(v101t.x(), v101t.y(), v101t.z());

glVertex3d(v110t.x(), v110t.y(), v110t.z());
glVertex3d(v111t.x(), v111t.y(), v111t.z());

glVertex3d(v010t.x(), v010t.y(), v010t.z());
glVertex3d(v011t.x(), v011t.y(), v011t.z());

//
glVertex3d(v000t.x(), v000t.y(), v000t.z());
glVertex3d(v110t.x(), v110t.y(), v110t.z());

glVertex3d(v010t.x(), v010t.y(), v010t.z());
glVertex3d(v100t.x(), v100t.y(), v100t.z());

glVertex3d(v001t.x(), v001t.y(), v001t.z());
glVertex3d(v111t.x(), v111t.y(), v111t.z());

glVertex3d(v011t.x(), v011t.y(), v011t.z());
glVertex3d(v101t.x(), v101t.y(), v101t.z());

glEnd();
}
void render();
};

class ObservationPicking
Expand All @@ -144,7 +53,7 @@ class ObservationPicking
void accept_current_observation(const std::vector<Eigen::Affine3d>& m_poses);
void import_observations(const std::string& filename);
void export_observation(const std::string& filename);
void add_intersection(Eigen::Vector3d translation);
void add_intersection(const Eigen::Vector3d& translation);

std::map<int, Eigen::Vector3d> current_observation;
std::vector<std::map<int, Eigen::Vector3d>> observations;
Expand Down
7 changes: 0 additions & 7 deletions core/include/Core/point_cloud.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@

#if WITH_GUI == 1
#include <Core/observation_picking.h>
#include <GL/freeglut.h>
#endif

class PointCloud
Expand Down Expand Up @@ -148,12 +147,6 @@ class PointCloud
void decimate(double bucket_x, double bucket_y, double bucket_z);
void shift_to_center();
#if WITH_GUI == 1
// void render(bool show_with_initial_pose, const ObservationPicking &observation_picking, int viewer_decmiate_point_cloud,
// bool xz_intersection, bool yz_intersection, bool xy_intersection,
// bool xz_grid_10x10, bool xz_grid_1x1, bool xz_grid_01x01,
// bool yz_grid_10x10, bool yz_grid_1x1, bool yz_grid_01x01,
// bool xy_grid_10x10, bool xy_grid_1x1, bool xy_grid_01x01,
// double intersection_width);
void render(
bool show_with_initial_pose,
const ObservationPicking& observation_picking,
Expand Down
24 changes: 14 additions & 10 deletions core/include/Core/registration_plane_feature.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,21 +24,25 @@ class RegistrationPlaneFeature

struct Plane
{
double a = {};
double b = {};
double c = {};
double d = {};

Plane()
: a(0.0)
, b(0.0)
, c(0.0)
, d(0.0)
{
a = b = c = d = 0.0;
}
double a;
double b;
double c;
double d;

Plane(Eigen::Vector3d p, Eigen::Vector3d nv)
Plane(const Eigen::Vector3d& p, const Eigen::Vector3d& nv)
: a(nv.x())
, b(nv.y())
, c(nv.z())
, d(-a * p.x() - b * p.y() - c * p.z())
{
a = nv.x();
b = nv.y();
c = nv.z();
d = -a * p.x() - b * p.y() - c * p.z();
}
};

Expand Down
61 changes: 14 additions & 47 deletions core/include/Core/structures.h
Original file line number Diff line number Diff line change
Expand Up @@ -172,43 +172,6 @@ bool save_vector_data(const std::string& file_name, const std::vector<T>& out)
}
}

/*template<typename T>
inline bool load_vector_data(const std::string& file_name, std::vector<T>& vector_data) {
std::basic_ifstream<char> vd_str(file_name, std::ios::binary);
if (!vd_str.good()) {
return false;
}
std::vector<char> data((std::istreambuf_iterator<char>(vd_str)), std::istreambuf_iterator<char>());
std::vector<T> v(data.size() / sizeof(T));
memcpy(v.data(), data.data(), data.size());
vector_data = v;
return true;
}*/

/*template<typename T>
bool load_vector_data(const std::string& file_name, std::vector<T>& out)
{
//static_assert(std::is_trivially_copyable_v<T>,
// "T must be trivially copyable");

std::ifstream file(file_name, std::ios::binary | std::ios::ate);
if (!file)
return false;

const std::streamsize size = file.tellg();
if (size < 0 || size % sizeof(T) != 0)
return false;

const size_t count = size / sizeof(T);
out.resize(count);

file.seekg(0, std::ios::beg);
if (!file.read(reinterpret_cast<char*>(out.data()), size))
return false;

return true;
}*/

template<typename T>
bool load_vector_data(const std::string& file_name, std::vector<T>& out)
{
Expand Down Expand Up @@ -264,21 +227,25 @@ struct LaserBeam

struct Plane
{
double a = {};
double b = {};
double c = {};
double d = {};

Plane()
: a(0.0)
, b(0.0)
, c(0.0)
, d(0.0)
{
a = b = c = d = 0.0;
}
double a;
double b;
double c;
double d;

Plane(Eigen::Vector3d p, Eigen::Vector3d nv)
Plane(const Eigen::Vector3d& p, const Eigen::Vector3d& nv)
: a(nv.x())
, b(nv.y())
, c(nv.z())
, d(-a * p.x() - b * p.y() - c * p.z())
{
a = nv.x();
b = nv.y();
c = nv.z();
d = -a * p.x() - b * p.y() - c * p.z();
}
};

Expand Down
Loading
Loading