Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Delete SubmapData from trimmed submaps in the OptimizationProblem. #366

Merged

Conversation

SirVer
Copy link
Contributor

@SirVer SirVer commented Jun 26, 2017

Related to #283.

@SirVer SirVer requested a review from wohe June 26, 2017 14:46
@@ -163,7 +171,9 @@ void OptimizationProblem::Solve(const std::vector<Constraint>& constraints) {
? new ceres::HuberLoss(options_.huber_scale())
: nullptr,
C_submaps.at(constraint.submap_id.trajectory_id)
.at(constraint.submap_id.submap_index)
.at(constraint.submap_id.submap_index -
trajectory_data_.at(constraint.node_id.trajectory_id)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

constraint.submap_id.trajectory_id otherwise multi-trajectory will not work correctly.

auto& trajectory_data = trajectory_data_.at(submap_id.trajectory_id);
// We only allow trimming from the start.
CHECK_EQ(trajectory_data.num_trimmed_submaps, submap_id.submap_index);
submap_data_.at(submap_id.trajectory_id).pop_front();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Similar to nodes: Extract submap_data and CHECK for non-empty?

@@ -199,7 +200,8 @@ class SparsePoseGraph : public mapping::SparsePoseGraph {
int num_trajectory_nodes_ GUARDED_BY(mutex_) = 0;

// Current submap transforms used for displaying data.
std::vector<std::vector<sparse_pose_graph::SubmapData>>
std::vector<int> num_trimmed_submaps_at_last_optimization_;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

GUARDED_BY(mutex_)?

@@ -402,10 +410,14 @@ void SparsePoseGraph::RunOptimization() {
node_data[trajectory_id][node_data_index].point_cloud_pose);
}
// Extrapolate all point cloud poses that were added later.
const auto local_to_new_global = ComputeLocalToGlobalTransform(
optimization_problem_.submap_data(), trajectory_id);
num_trimmed_submaps.push_back(
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Make a separate loop over the trajectories in submap_data()?

@SirVer SirVer force-pushed the 01_cleanup_optimization_problem branch from 11a0944 to 7f27b9e Compare June 27, 2017 11:55
.at(submap_id.submap_index)
.pose)};
static_cast<int>(optimized_submap_transforms_.size())) {
const size_t submap_index =
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

submap_data_index?

@@ -511,18 +532,23 @@ mapping::SparsePoseGraph::SubmapData SparsePoseGraph::GetSubmapDataUnderLock(
auto submap = submap_data_.at(submap_id).submap;
// We already have an optimized pose.
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Move to the nested if?

@SirVer SirVer force-pushed the 01_cleanup_optimization_problem branch from bee1f59 to bc253a7 Compare June 27, 2017 15:53
@wohe wohe merged commit 471bcb6 into cartographer-project:master Jun 28, 2017
@SirVer SirVer deleted the 01_cleanup_optimization_problem branch July 3, 2017 09:18
damienrg pushed a commit to damienrg/cartographer that referenced this pull request Nov 8, 2017
Rviz has a limit of 16384 points per marker. To get around this, each
trajectory is split into multiple markers, each up to 16384 points.
Fixes cartographer-project#366.
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

3 participants