pose_graph.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 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/mapping/pose_graph.h"
00018 
00019 #include "cartographer/mapping/internal/constraints/constraint_builder.h"
00020 #include "cartographer/mapping/internal/optimization/optimization_problem_options.h"
00021 #include "cartographer/transform/transform.h"
00022 #include "glog/logging.h"
00023 
00024 namespace cartographer {
00025 namespace mapping {
00026 
00027 proto::PoseGraph::Constraint::Tag ToProto(
00028     const PoseGraph::Constraint::Tag& tag) {
00029   switch (tag) {
00030     case PoseGraph::Constraint::Tag::INTRA_SUBMAP:
00031       return proto::PoseGraph::Constraint::INTRA_SUBMAP;
00032     case PoseGraph::Constraint::Tag::INTER_SUBMAP:
00033       return proto::PoseGraph::Constraint::INTER_SUBMAP;
00034   }
00035   LOG(FATAL) << "Unsupported tag.";
00036 }
00037 
00038 PoseGraph::Constraint::Tag FromProto(
00039     const proto::PoseGraph::Constraint::Tag& proto) {
00040   switch (proto) {
00041     case proto::PoseGraph::Constraint::INTRA_SUBMAP:
00042       return PoseGraph::Constraint::Tag::INTRA_SUBMAP;
00043     case proto::PoseGraph::Constraint::INTER_SUBMAP:
00044       return PoseGraph::Constraint::Tag::INTER_SUBMAP;
00045     case ::google::protobuf::kint32max:
00046     case ::google::protobuf::kint32min: {
00047     }
00048   }
00049   LOG(FATAL) << "Unsupported tag.";
00050 }
00051 
00052 std::vector<PoseGraph::Constraint> FromProto(
00053     const ::google::protobuf::RepeatedPtrField<proto::PoseGraph::Constraint>&
00054         constraint_protos) {
00055   std::vector<PoseGraph::Constraint> constraints;
00056   for (const auto& constraint_proto : constraint_protos) {
00057     const mapping::SubmapId submap_id{
00058         constraint_proto.submap_id().trajectory_id(),
00059         constraint_proto.submap_id().submap_index()};
00060     const mapping::NodeId node_id{constraint_proto.node_id().trajectory_id(),
00061                                   constraint_proto.node_id().node_index()};
00062     const PoseGraph::Constraint::Pose pose{
00063         transform::ToRigid3(constraint_proto.relative_pose()),
00064         constraint_proto.translation_weight(),
00065         constraint_proto.rotation_weight()};
00066     const PoseGraph::Constraint::Tag tag = FromProto(constraint_proto.tag());
00067     constraints.push_back(PoseGraph::Constraint{submap_id, node_id, pose, tag});
00068   }
00069   return constraints;
00070 }
00071 
00072 void PopulateOverlappingSubmapsTrimmerOptions2D(
00073     proto::PoseGraphOptions* const pose_graph_options,
00074     common::LuaParameterDictionary* const parameter_dictionary) {
00075   constexpr char kDictionaryKey[] = "overlapping_submaps_trimmer_2d";
00076   if (!parameter_dictionary->HasKey(kDictionaryKey)) return;
00077 
00078   auto options_dictionary = parameter_dictionary->GetDictionary(kDictionaryKey);
00079   auto* options = pose_graph_options->mutable_overlapping_submaps_trimmer_2d();
00080   options->set_fresh_submaps_count(
00081       options_dictionary->GetInt("fresh_submaps_count"));
00082   options->set_min_covered_area(
00083       options_dictionary->GetDouble("min_covered_area"));
00084   options->set_min_added_submaps_count(
00085       options_dictionary->GetInt("min_added_submaps_count"));
00086 }
00087 
00088 proto::PoseGraphOptions CreatePoseGraphOptions(
00089     common::LuaParameterDictionary* const parameter_dictionary) {
00090   proto::PoseGraphOptions options;
00091   options.set_optimize_every_n_nodes(
00092       parameter_dictionary->GetInt("optimize_every_n_nodes"));
00093   *options.mutable_constraint_builder_options() =
00094       constraints::CreateConstraintBuilderOptions(
00095           parameter_dictionary->GetDictionary("constraint_builder").get());
00096   options.set_matcher_translation_weight(
00097       parameter_dictionary->GetDouble("matcher_translation_weight"));
00098   options.set_matcher_rotation_weight(
00099       parameter_dictionary->GetDouble("matcher_rotation_weight"));
00100   *options.mutable_optimization_problem_options() =
00101       optimization::CreateOptimizationProblemOptions(
00102           parameter_dictionary->GetDictionary("optimization_problem").get());
00103   options.set_max_num_final_iterations(
00104       parameter_dictionary->GetNonNegativeInt("max_num_final_iterations"));
00105   CHECK_GT(options.max_num_final_iterations(), 0);
00106   options.set_global_sampling_ratio(
00107       parameter_dictionary->GetDouble("global_sampling_ratio"));
00108   options.set_log_residual_histograms(
00109       parameter_dictionary->GetBool("log_residual_histograms"));
00110   options.set_global_constraint_search_after_n_seconds(
00111       parameter_dictionary->GetDouble(
00112           "global_constraint_search_after_n_seconds"));
00113   PopulateOverlappingSubmapsTrimmerOptions2D(&options, parameter_dictionary);
00114   return options;
00115 }
00116 
00117 proto::PoseGraph::Constraint ToProto(const PoseGraph::Constraint& constraint) {
00118   proto::PoseGraph::Constraint constraint_proto;
00119   *constraint_proto.mutable_relative_pose() =
00120       transform::ToProto(constraint.pose.zbar_ij);
00121   constraint_proto.set_translation_weight(constraint.pose.translation_weight);
00122   constraint_proto.set_rotation_weight(constraint.pose.rotation_weight);
00123   constraint_proto.mutable_submap_id()->set_trajectory_id(
00124       constraint.submap_id.trajectory_id);
00125   constraint_proto.mutable_submap_id()->set_submap_index(
00126       constraint.submap_id.submap_index);
00127   constraint_proto.mutable_node_id()->set_trajectory_id(
00128       constraint.node_id.trajectory_id);
00129   constraint_proto.mutable_node_id()->set_node_index(
00130       constraint.node_id.node_index);
00131   constraint_proto.set_tag(mapping::ToProto(constraint.tag));
00132   return constraint_proto;
00133 }
00134 
00135 proto::PoseGraph PoseGraph::ToProto(bool include_unfinished_submaps) const {
00136   proto::PoseGraph proto;
00137 
00138   std::map<int, proto::Trajectory* const> trajectory_protos;
00139   const auto trajectory = [&proto, &trajectory_protos](
00140                               const int trajectory_id) -> proto::Trajectory* {
00141     if (trajectory_protos.count(trajectory_id) == 0) {
00142       auto* const trajectory_proto = proto.add_trajectory();
00143       trajectory_proto->set_trajectory_id(trajectory_id);
00144       CHECK(trajectory_protos.emplace(trajectory_id, trajectory_proto).second);
00145     }
00146     return trajectory_protos.at(trajectory_id);
00147   };
00148 
00149   std::set<mapping::SubmapId> unfinished_submaps;
00150   for (const auto& submap_id_data : GetAllSubmapData()) {
00151     proto::Trajectory* trajectory_proto =
00152         trajectory(submap_id_data.id.trajectory_id);
00153     if (!include_unfinished_submaps &&
00154         !submap_id_data.data.submap->insertion_finished()) {
00155       // Collect IDs of all unfinished submaps and skip them.
00156       unfinished_submaps.insert(submap_id_data.id);
00157       continue;
00158     }
00159     CHECK(submap_id_data.data.submap != nullptr);
00160     auto* const submap_proto = trajectory_proto->add_submap();
00161     submap_proto->set_submap_index(submap_id_data.id.submap_index);
00162     *submap_proto->mutable_pose() =
00163         transform::ToProto(submap_id_data.data.pose);
00164   }
00165 
00166   auto constraints_copy = constraints();
00167   std::set<mapping::NodeId> orphaned_nodes;
00168   proto.mutable_constraint()->Reserve(constraints_copy.size());
00169   for (auto it = constraints_copy.begin(); it != constraints_copy.end();) {
00170     if (!include_unfinished_submaps &&
00171         unfinished_submaps.count(it->submap_id) > 0) {
00172       // Skip all those constraints that refer to unfinished submaps and
00173       // remember the corresponding trajectory nodes as potentially orphaned.
00174       orphaned_nodes.insert(it->node_id);
00175       it = constraints_copy.erase(it);
00176       continue;
00177     }
00178     *proto.add_constraint() = cartographer::mapping::ToProto(*it);
00179     ++it;
00180   }
00181 
00182   if (!include_unfinished_submaps) {
00183     // Iterate over all constraints and remove trajectory nodes from
00184     // 'orphaned_nodes' that are not actually orphaned.
00185     for (const auto& constraint : constraints_copy) {
00186       orphaned_nodes.erase(constraint.node_id);
00187     }
00188   }
00189 
00190   for (const auto& node_id_data : GetTrajectoryNodes()) {
00191     proto::Trajectory* trajectory_proto =
00192         trajectory(node_id_data.id.trajectory_id);
00193     CHECK(node_id_data.data.constant_data != nullptr);
00194     auto* const node_proto = trajectory_proto->add_node();
00195     node_proto->set_node_index(node_id_data.id.node_index);
00196     node_proto->set_timestamp(
00197         common::ToUniversal(node_id_data.data.constant_data->time));
00198     *node_proto->mutable_pose() =
00199         transform::ToProto(node_id_data.data.global_pose);
00200   }
00201 
00202   auto landmarks_copy = GetLandmarkPoses();
00203   proto.mutable_landmark_poses()->Reserve(landmarks_copy.size());
00204   for (const auto& id_pose : landmarks_copy) {
00205     auto* landmark_proto = proto.add_landmark_poses();
00206     landmark_proto->set_landmark_id(id_pose.first);
00207     *landmark_proto->mutable_global_pose() = transform::ToProto(id_pose.second);
00208   }
00209   return proto;
00210 }
00211 
00212 }  // namespace mapping
00213 }  // namespace cartographer


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