Skip to content

Commit

Permalink
Viewer config (#79)
Browse files Browse the repository at this point in the history
* viewer config

* fix pose jitters
  • Loading branch information
koide3 authored Sep 22, 2024
1 parent 7a05836 commit c49a3e8
Show file tree
Hide file tree
Showing 6 changed files with 79 additions and 15 deletions.
14 changes: 12 additions & 2 deletions config/config_viewer.json
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,12 @@
4.0
],
"enable_partial_rendering": false,
"partial_rendering_budget": 1024
"partial_rendering_budget": 1024,
"point_shape_circle": true,
"point_size_metric": false,
"point_size": 10.0,
"points_alpha": 0.5,
"factors_alpha": 0.5
},
"interactive_viewer": {
"viewer_width": 2560,
Expand All @@ -23,6 +28,11 @@
4.0
],
"enable_partial_rendering": false,
"partial_rendering_budget": 1024
"partial_rendering_budget": 1024,
"point_shape_circle": true,
"point_size_metric": false,
"point_size": 10.0,
"points_alpha": 0.5,
"factors_alpha": 0.5
}
}
7 changes: 7 additions & 0 deletions include/glim/viewer/interactive_viewer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,8 +94,15 @@ class InteractiveViewer : public ExtensionModule {
bool enable_partial_rendering;
int partial_rendering_budget;

double point_size;
bool point_size_metric;
bool point_shape_circle;

Eigen::Vector2f z_range;

double points_alpha;
double factors_alpha;

// Click information
Eigen::Vector4i right_clicked_info;
Eigen::Vector3f right_clicked_pos;
Expand Down
6 changes: 6 additions & 0 deletions include/glim/viewer/standard_viewer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,8 +79,14 @@ class StandardViewer : public ExtensionModule {
std::vector<std::pair<boost::weak_ptr<gtsam::NonlinearFactor>, FactorLineGetter>> odometry_factor_lines;
std::unordered_map<std::uint64_t, Eigen::Isometry3f> odometry_poses;

double point_size;
bool point_size_metric;
bool point_shape_circle;

Eigen::Vector2f z_range;
Eigen::Vector2f auto_z_range;
double points_alpha;
double factors_alpha;

std::unique_ptr<TrajectoryManager> trajectory;
std::vector<Eigen::Isometry3f> submap_keyframes;
Expand Down
2 changes: 1 addition & 1 deletion src/glim/util/trajectory_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ void TrajectoryManager::update_anchor(double stamp, const Eigen::Isometry3d& T_w
const double t0 = odom_stamps[idx - 1];
const double t1 = odom_stamps[idx];
if (t0 > stamp || t1 < stamp) {
T_world_odom = T_world_sensor * T_odom_sensor[idx].inverse();
// T_world_odom = T_world_sensor * T_odom_sensor[idx].inverse();
return;
}

Expand Down
27 changes: 22 additions & 5 deletions src/glim/viewer/interactive_viewer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,13 @@ InteractiveViewer::InteractiveViewer() : logger(create_module_logger("viewer"))
enable_partial_rendering = config.param("interactive_viewer", "enable_partial_rendering", false);
partial_rendering_budget = config.param("interactive_viewer", "partial_rendering_budget", 1024);

points_alpha = config.param("interactive_viewer", "points_alpha", 1.0);
factors_alpha = config.param("interactive_viewer", "factors_alpha", 1.0);

point_size = config.param("interactive_viewer", "point_size", 1.0);
point_size_metric = config.param("interactive_viewer", "point_size_metric", false);
point_shape_circle = config.param("interactive_viewer", "point_shape_circle", true);

z_range = config.param("interactive_viewer", "default_z_range", Eigen::Vector2d(-2.0, 4.0)).cast<float>();

trajectory.reset(new TrajectoryManager);
Expand Down Expand Up @@ -90,6 +97,16 @@ void InteractiveViewer::viewer_loop() {
viewer->enable_vsync();
viewer->shader_setting().add("z_range", z_range);

viewer->shader_setting().set_point_size(point_size);

if (point_size_metric) {
viewer->shader_setting().set_point_scale_metric();
}

if (point_shape_circle) {
viewer->shader_setting().set_point_shape_circle();
}

if (enable_partial_rendering) {
viewer->enable_partial_rendering(0.1);
viewer->shader_setting().add("dynamic_object", 1);
Expand Down Expand Up @@ -289,7 +306,7 @@ void InteractiveViewer::update_viewer() {
} else {
const Eigen::Vector4i info(static_cast<int>(PickType::POINTS), 0, 0, submap->id);
auto cloud_buffer = std::make_shared<glk::PointCloudBuffer>(submap->frame->points, submap->frame->size());
auto shader_setting = guik::Rainbow(submap_pose).add("info_values", info);
auto shader_setting = guik::Rainbow(submap_pose).add("info_values", info).set_alpha(points_alpha);

if (enable_partial_rendering) {
cloud_buffer->enable_partial_rendering(partial_rendering_budget);
Expand Down Expand Up @@ -348,21 +365,21 @@ void InteractiveViewer::update_viewer() {
Eigen::Vector4f color;
switch (type) {
case FactorType::MATCHING_COST:
color = Eigen::Vector4f(0.0f, 1.0f, 0.0f, 1.0f);
color = Eigen::Vector4f(0.0f, 1.0f, 0.0f, factors_alpha);
break;
case FactorType::BETWEEN:
color = Eigen::Vector4f(0.0f, 0.0f, 1.0f, 1.0f);
color = Eigen::Vector4f(0.0f, 0.0f, 1.0f, factors_alpha);
break;
case FactorType::IMU:
color = Eigen::Vector4f(1.0f, 0.0f, 0.0f, 1.0f);
color = Eigen::Vector4f(1.0f, 0.0f, 0.0f, factors_alpha);
break;
}

factor_colors.push_back(color);
factor_colors.push_back(color);
}

viewer->update_drawable("factors", std::make_shared<glk::ThinLines>(factor_lines, factor_colors), guik::VertexColor());
viewer->update_drawable("factors", std::make_shared<glk::ThinLines>(factor_lines, factor_colors), guik::VertexColor().set_alpha(factors_alpha));

std::vector<Eigen::Vector3f> traj;
for (const auto& submap : submaps) {
Expand Down
38 changes: 31 additions & 7 deletions src/glim/viewer/standard_viewer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,13 @@ StandardViewer::StandardViewer() : logger(create_module_logger("viewer")) {
z_range = config.param("standard_viewer", "default_z_range", Eigen::Vector2d(-2.0, 4.0)).cast<float>();
auto_z_range << 0.0f, 0.0f;

points_alpha = config.param("standard_viewer", "points_alpha", 1.0);
factors_alpha = config.param("standard_viewer", "factors_alpha", 1.0);

point_size = config.param("standard_viewer", "point_size", 1.0);
point_size_metric = config.param("standard_viewer", "point_size_metric", false);
point_shape_circle = config.param("standard_viewer", "point_shape_circle", true);

trajectory.reset(new TrajectoryManager);

enable_partial_rendering = config.param("standard_viewer", "enable_partial_rendering", false);
Expand Down Expand Up @@ -265,7 +272,11 @@ void StandardViewer::set_callbacks() {
}

const Eigen::Vector3d pt1 = static_cast<const gtsam_points::IntegratedMatchingCostFactor*>(factor)->get_fixed_target_pose().translation();
return std::make_tuple(found0->second.translation(), pt1.cast<float>(), Eigen::Vector4f(0.0f, 1.0f, 0.0f, 0.5f), Eigen::Vector4f(1.0f, 0.0f, 0.0f, 0.5f));
return std::make_tuple(
found0->second.translation(),
pt1.cast<float>(),
Eigen::Vector4f(0.0f, 1.0f, 0.0f, factors_alpha),
Eigen::Vector4f(1.0f, 0.0f, 0.0f, factors_alpha));
};

new_factor_lines.emplace_back(factor, l);
Expand All @@ -282,7 +293,7 @@ void StandardViewer::set_callbacks() {
}

const Eigen::Vector3f pt1 = static_cast<const gtsam_points::IntegratedVGICPFactorGPU*>(factor)->get_fixed_target_pose().translation();
return std::make_tuple(found0->second.translation(), pt1, Eigen::Vector4f(0.0f, 1.0f, 0.0f, 0.5f), Eigen::Vector4f(1.0f, 0.0f, 0.0f, 0.5f));
return std::make_tuple(found0->second.translation(), pt1, Eigen::Vector4f(0.0f, 1.0f, 0.0f, factors_alpha), Eigen::Vector4f(1.0f, 0.0f, 0.0f, factors_alpha));
};

new_factor_lines.emplace_back(factor, l);
Expand All @@ -306,7 +317,11 @@ void StandardViewer::set_callbacks() {
return std::nullopt;
}

return std::make_tuple(found0->second.translation(), found1->second.translation(), Eigen::Vector4f(0.0f, 1.0f, 0.0f, 1.0f), Eigen::Vector4f(0.0f, 1.0f, 0.0f, 1.0f));
return std::make_tuple(
found0->second.translation(),
found1->second.translation(),
Eigen::Vector4f(0.0f, 1.0f, 0.0f, factors_alpha),
Eigen::Vector4f(0.0f, 1.0f, 0.0f, factors_alpha));
};

new_factor_lines.emplace_back(factor, l);
Expand Down Expand Up @@ -342,7 +357,7 @@ void StandardViewer::set_callbacks() {
}

auto viewer = guik::viewer();
viewer->update_drawable("odometry_factors", std::make_shared<glk::ThinLines>(line_vertices, line_colors), guik::VertexColor().make_transparent());
viewer->update_drawable("odometry_factors", std::make_shared<glk::ThinLines>(line_vertices, line_colors), guik::VertexColor().set_alpha(factors_alpha));
});
});

Expand Down Expand Up @@ -461,7 +476,7 @@ void StandardViewer::set_callbacks() {
lines.push_back(submap_keyframes[factor.second].translation());
}

sub_viewer->update_drawable("factors", std::make_shared<glk::ThinLines>(lines), guik::FlatGreen());
sub_viewer->update_drawable("factors", std::make_shared<glk::ThinLines>(lines), guik::FlatGreen().set_alpha(factors_alpha));
});
});

Expand All @@ -486,7 +501,7 @@ void StandardViewer::set_callbacks() {
auto viewer = guik::LightViewer::instance();
auto cloud_buffer = std::make_shared<glk::PointCloudBuffer>(submap->frame->points, submap->frame->size());
auto shader_setting = guik::Rainbow(T_world_origin->matrix().cast<float>());
shader_setting.add("point_scale", 0.1f);
shader_setting.set_alpha(points_alpha);

if (enable_partial_rendering) {
cloud_buffer->enable_partial_rendering(partial_rendering_budget);
Expand Down Expand Up @@ -535,7 +550,7 @@ void StandardViewer::set_callbacks() {
}
}

viewer->update_drawable("factors", std::make_shared<glk::ThinLines>(submap_positions, indices), guik::FlatGreen());
viewer->update_drawable("factors", std::make_shared<glk::ThinLines>(submap_positions, indices), guik::FlatGreen().set_alpha(factors_alpha));
viewer->shader_setting().add<Eigen::Vector2f>("z_range", auto_z_range + z_range);
});
});
Expand Down Expand Up @@ -573,6 +588,15 @@ void StandardViewer::viewer_loop() {
auto viewer = guik::LightViewer::instance(Eigen::Vector2i(config.param("standard_viewer", "viewer_width", 2560), config.param("standard_viewer", "viewer_height", 1440)));
viewer->enable_vsync();
viewer->shader_setting().add("z_range", z_range);
viewer->shader_setting().set_point_size(point_size);

if (point_size_metric) {
viewer->shader_setting().set_point_scale_metric();
}

if (point_shape_circle) {
viewer->shader_setting().set_point_shape_circle();
}

if (enable_partial_rendering) {
viewer->enable_partial_rendering(1e-1);
Expand Down

0 comments on commit c49a3e8

Please sign in to comment.