autogenerate_ground_truth.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2018 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include "cartographer/ground_truth/autogenerate_ground_truth.h"
00018 
00019 #include <string>
00020 #include <vector>
00021 
00022 #include "cartographer/mapping/proto/trajectory.pb.h"
00023 #include "cartographer/transform/transform.h"
00024 #include "glog/logging.h"
00025 
00026 namespace cartographer {
00027 namespace ground_truth {
00028 namespace {
00029 
00030 std::vector<double> ComputeCoveredDistance(
00031     const mapping::proto::Trajectory& trajectory) {
00032   std::vector<double> covered_distance;
00033   covered_distance.push_back(0.);
00034   CHECK_GT(trajectory.node_size(), 0)
00035       << "Trajectory does not contain any nodes.";
00036   for (int i = 1; i < trajectory.node_size(); ++i) {
00037     const auto last_pose = transform::ToRigid3(trajectory.node(i - 1).pose());
00038     const auto this_pose = transform::ToRigid3(trajectory.node(i).pose());
00039     covered_distance.push_back(
00040         covered_distance.back() +
00041         (last_pose.inverse() * this_pose).translation().norm());
00042   }
00043   return covered_distance;
00044 }
00045 
00046 // We pick the representative node in the middle of the submap.
00047 //
00048 // TODO(whess): Should we consider all nodes inserted into the submap and
00049 // exclude, e.g. based on large relative linear or angular distance?
00050 std::vector<int> ComputeSubmapRepresentativeNode(
00051     const mapping::proto::PoseGraph& pose_graph) {
00052   std::vector<int> submap_to_node_index;
00053   for (const auto& constraint : pose_graph.constraint()) {
00054     if (constraint.tag() !=
00055         mapping::proto::PoseGraph::Constraint::INTRA_SUBMAP) {
00056       continue;
00057     }
00058     CHECK_EQ(constraint.submap_id().trajectory_id(), 0);
00059     CHECK_EQ(constraint.node_id().trajectory_id(), 0);
00060 
00061     const int next_submap_index = static_cast<int>(submap_to_node_index.size());
00062     const int submap_index = constraint.submap_id().submap_index();
00063     if (submap_index <= next_submap_index) {
00064       continue;
00065     }
00066 
00067     CHECK_EQ(submap_index, next_submap_index + 1);
00068     submap_to_node_index.push_back(constraint.node_id().node_index());
00069   }
00070   return submap_to_node_index;
00071 }
00072 
00073 }  // namespace
00074 
00075 proto::GroundTruth GenerateGroundTruth(
00076     const mapping::proto::PoseGraph& pose_graph,
00077     const double min_covered_distance, const double outlier_threshold_meters,
00078     const double outlier_threshold_radians) {
00079   const mapping::proto::Trajectory& trajectory = pose_graph.trajectory(0);
00080   const std::vector<double> covered_distance =
00081       ComputeCoveredDistance(trajectory);
00082 
00083   const std::vector<int> submap_to_node_index =
00084       ComputeSubmapRepresentativeNode(pose_graph);
00085 
00086   int num_outliers = 0;
00087   proto::GroundTruth ground_truth;
00088   for (const auto& constraint : pose_graph.constraint()) {
00089     // We're only interested in loop closure constraints.
00090     if (constraint.tag() ==
00091         mapping::proto::PoseGraph::Constraint::INTRA_SUBMAP) {
00092       continue;
00093     }
00094 
00095     // For some submaps at the very end, we have not chosen a representative
00096     // node, but those should not be part of loop closure anyway.
00097     CHECK_EQ(constraint.submap_id().trajectory_id(), 0);
00098     CHECK_EQ(constraint.node_id().trajectory_id(), 0);
00099     if (constraint.submap_id().submap_index() >=
00100         static_cast<int>(submap_to_node_index.size())) {
00101       continue;
00102     }
00103     const int matched_node = constraint.node_id().node_index();
00104     const int representative_node =
00105         submap_to_node_index.at(constraint.submap_id().submap_index());
00106 
00107     // Covered distance between the two should not be too small.
00108     double covered_distance_in_constraint =
00109         std::abs(covered_distance.at(matched_node) -
00110                  covered_distance.at(representative_node));
00111     if (covered_distance_in_constraint < min_covered_distance) {
00112       continue;
00113     }
00114 
00115     // Compute the transform between the nodes according to the solution and
00116     // the constraint.
00117     const transform::Rigid3d solution_pose1 =
00118         transform::ToRigid3(trajectory.node(representative_node).pose());
00119     const transform::Rigid3d solution_pose2 =
00120         transform::ToRigid3(trajectory.node(matched_node).pose());
00121     const transform::Rigid3d solution =
00122         solution_pose1.inverse() * solution_pose2;
00123 
00124     const transform::Rigid3d submap_solution = transform::ToRigid3(
00125         trajectory.submap(constraint.submap_id().submap_index()).pose());
00126     const transform::Rigid3d submap_solution_to_node_solution =
00127         solution_pose1.inverse() * submap_solution;
00128     const transform::Rigid3d node_to_submap_constraint =
00129         transform::ToRigid3(constraint.relative_pose());
00130     const transform::Rigid3d expected =
00131         submap_solution_to_node_solution * node_to_submap_constraint;
00132 
00133     const transform::Rigid3d error = solution * expected.inverse();
00134 
00135     if (error.translation().norm() > outlier_threshold_meters ||
00136         transform::GetAngle(error) > outlier_threshold_radians) {
00137       ++num_outliers;
00138       continue;
00139     }
00140     auto* const new_relation = ground_truth.add_relation();
00141     new_relation->set_timestamp1(
00142         trajectory.node(representative_node).timestamp());
00143     new_relation->set_timestamp2(trajectory.node(matched_node).timestamp());
00144     *new_relation->mutable_expected() = transform::ToProto(expected);
00145     new_relation->set_covered_distance(covered_distance_in_constraint);
00146   }
00147   LOG(INFO) << "Generated " << ground_truth.relation_size()
00148             << " relations and ignored " << num_outliers << " outliers.";
00149   return ground_truth;
00150 }
00151 
00152 }  // namespace ground_truth
00153 }  // namespace cartographer


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35