00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include "cartographer/mapping/map_builder.h"
00018
00019 #include "absl/memory/memory.h"
00020 #include "cartographer/common/time.h"
00021 #include "cartographer/io/internal/mapping_state_serialization.h"
00022 #include "cartographer/io/proto_stream.h"
00023 #include "cartographer/io/proto_stream_deserializer.h"
00024 #include "cartographer/io/serialization_format_migration.h"
00025 #include "cartographer/mapping/internal/2d/local_trajectory_builder_2d.h"
00026 #include "cartographer/mapping/internal/2d/pose_graph_2d.h"
00027 #include "cartographer/mapping/internal/3d/local_trajectory_builder_3d.h"
00028 #include "cartographer/mapping/internal/3d/pose_graph_3d.h"
00029 #include "cartographer/mapping/internal/collated_trajectory_builder.h"
00030 #include "cartographer/mapping/internal/global_trajectory_builder.h"
00031 #include "cartographer/mapping/proto/internal/legacy_serialized_data.pb.h"
00032 #include "cartographer/sensor/internal/collator.h"
00033 #include "cartographer/sensor/internal/trajectory_collator.h"
00034 #include "cartographer/sensor/internal/voxel_filter.h"
00035 #include "cartographer/transform/rigid_transform.h"
00036 #include "cartographer/transform/transform.h"
00037
00038 namespace cartographer {
00039 namespace mapping {
00040 namespace {
00041
00042 using mapping::proto::SerializedData;
00043
00044 std::vector<std::string> SelectRangeSensorIds(
00045 const std::set<MapBuilder::SensorId>& expected_sensor_ids) {
00046 std::vector<std::string> range_sensor_ids;
00047 for (const MapBuilder::SensorId& sensor_id : expected_sensor_ids) {
00048 if (sensor_id.type == MapBuilder::SensorId::SensorType::RANGE) {
00049 range_sensor_ids.push_back(sensor_id.id);
00050 }
00051 }
00052 return range_sensor_ids;
00053 }
00054
00055 void MaybeAddPureLocalizationTrimmer(
00056 const int trajectory_id,
00057 const proto::TrajectoryBuilderOptions& trajectory_options,
00058 PoseGraph* pose_graph) {
00059 if (trajectory_options.pure_localization()) {
00060 LOG(WARNING)
00061 << "'TrajectoryBuilderOptions::pure_localization' field is deprecated. "
00062 "Use 'TrajectoryBuilderOptions::pure_localization_trimmer' instead.";
00063 pose_graph->AddTrimmer(absl::make_unique<PureLocalizationTrimmer>(
00064 trajectory_id, 3 ));
00065 return;
00066 }
00067 if (trajectory_options.has_pure_localization_trimmer()) {
00068 pose_graph->AddTrimmer(absl::make_unique<PureLocalizationTrimmer>(
00069 trajectory_id,
00070 trajectory_options.pure_localization_trimmer().max_submaps_to_keep()));
00071 }
00072 }
00073
00074 }
00075
00076 proto::MapBuilderOptions CreateMapBuilderOptions(
00077 common::LuaParameterDictionary* const parameter_dictionary) {
00078 proto::MapBuilderOptions options;
00079 options.set_use_trajectory_builder_2d(
00080 parameter_dictionary->GetBool("use_trajectory_builder_2d"));
00081 options.set_use_trajectory_builder_3d(
00082 parameter_dictionary->GetBool("use_trajectory_builder_3d"));
00083 options.set_num_background_threads(
00084 parameter_dictionary->GetNonNegativeInt("num_background_threads"));
00085 options.set_collate_by_trajectory(
00086 parameter_dictionary->GetBool("collate_by_trajectory"));
00087 *options.mutable_pose_graph_options() = CreatePoseGraphOptions(
00088 parameter_dictionary->GetDictionary("pose_graph").get());
00089 CHECK_NE(options.use_trajectory_builder_2d(),
00090 options.use_trajectory_builder_3d());
00091 return options;
00092 }
00093
00094 MapBuilder::MapBuilder(const proto::MapBuilderOptions& options)
00095 : options_(options), thread_pool_(options.num_background_threads()) {
00096 CHECK(options.use_trajectory_builder_2d() ^
00097 options.use_trajectory_builder_3d());
00098 if (options.use_trajectory_builder_2d()) {
00099 pose_graph_ = absl::make_unique<PoseGraph2D>(
00100 options_.pose_graph_options(),
00101 absl::make_unique<optimization::OptimizationProblem2D>(
00102 options_.pose_graph_options().optimization_problem_options()),
00103 &thread_pool_);
00104 }
00105 if (options.use_trajectory_builder_3d()) {
00106 pose_graph_ = absl::make_unique<PoseGraph3D>(
00107 options_.pose_graph_options(),
00108 absl::make_unique<optimization::OptimizationProblem3D>(
00109 options_.pose_graph_options().optimization_problem_options()),
00110 &thread_pool_);
00111 }
00112 if (options.collate_by_trajectory()) {
00113 sensor_collator_ = absl::make_unique<sensor::TrajectoryCollator>();
00114 } else {
00115 sensor_collator_ = absl::make_unique<sensor::Collator>();
00116 }
00117 }
00118
00119 int MapBuilder::AddTrajectoryBuilder(
00120 const std::set<SensorId>& expected_sensor_ids,
00121 const proto::TrajectoryBuilderOptions& trajectory_options,
00122 LocalSlamResultCallback local_slam_result_callback) {
00123 const int trajectory_id = trajectory_builders_.size();
00124 if (options_.use_trajectory_builder_3d()) {
00125 std::unique_ptr<LocalTrajectoryBuilder3D> local_trajectory_builder;
00126 if (trajectory_options.has_trajectory_builder_3d_options()) {
00127 local_trajectory_builder = absl::make_unique<LocalTrajectoryBuilder3D>(
00128 trajectory_options.trajectory_builder_3d_options(),
00129 SelectRangeSensorIds(expected_sensor_ids));
00130 }
00131 DCHECK(dynamic_cast<PoseGraph3D*>(pose_graph_.get()));
00132 trajectory_builders_.push_back(absl::make_unique<CollatedTrajectoryBuilder>(
00133 trajectory_options, sensor_collator_.get(), trajectory_id,
00134 expected_sensor_ids,
00135 CreateGlobalTrajectoryBuilder3D(
00136 std::move(local_trajectory_builder), trajectory_id,
00137 static_cast<PoseGraph3D*>(pose_graph_.get()),
00138 local_slam_result_callback)));
00139 } else {
00140 std::unique_ptr<LocalTrajectoryBuilder2D> local_trajectory_builder;
00141 if (trajectory_options.has_trajectory_builder_2d_options()) {
00142 local_trajectory_builder = absl::make_unique<LocalTrajectoryBuilder2D>(
00143 trajectory_options.trajectory_builder_2d_options(),
00144 SelectRangeSensorIds(expected_sensor_ids));
00145 }
00146 DCHECK(dynamic_cast<PoseGraph2D*>(pose_graph_.get()));
00147 trajectory_builders_.push_back(absl::make_unique<CollatedTrajectoryBuilder>(
00148 trajectory_options, sensor_collator_.get(), trajectory_id,
00149 expected_sensor_ids,
00150 CreateGlobalTrajectoryBuilder2D(
00151 std::move(local_trajectory_builder), trajectory_id,
00152 static_cast<PoseGraph2D*>(pose_graph_.get()),
00153 local_slam_result_callback)));
00154 }
00155 MaybeAddPureLocalizationTrimmer(trajectory_id, trajectory_options,
00156 pose_graph_.get());
00157
00158 if (trajectory_options.has_initial_trajectory_pose()) {
00159 const auto& initial_trajectory_pose =
00160 trajectory_options.initial_trajectory_pose();
00161 pose_graph_->SetInitialTrajectoryPose(
00162 trajectory_id, initial_trajectory_pose.to_trajectory_id(),
00163 transform::ToRigid3(initial_trajectory_pose.relative_pose()),
00164 common::FromUniversal(initial_trajectory_pose.timestamp()));
00165 }
00166 proto::TrajectoryBuilderOptionsWithSensorIds options_with_sensor_ids_proto;
00167 for (const auto& sensor_id : expected_sensor_ids) {
00168 *options_with_sensor_ids_proto.add_sensor_id() = ToProto(sensor_id);
00169 }
00170 *options_with_sensor_ids_proto.mutable_trajectory_builder_options() =
00171 trajectory_options;
00172 all_trajectory_builder_options_.push_back(options_with_sensor_ids_proto);
00173 CHECK_EQ(trajectory_builders_.size(), all_trajectory_builder_options_.size());
00174 return trajectory_id;
00175 }
00176
00177 int MapBuilder::AddTrajectoryForDeserialization(
00178 const proto::TrajectoryBuilderOptionsWithSensorIds&
00179 options_with_sensor_ids_proto) {
00180 const int trajectory_id = trajectory_builders_.size();
00181 trajectory_builders_.emplace_back();
00182 all_trajectory_builder_options_.push_back(options_with_sensor_ids_proto);
00183 CHECK_EQ(trajectory_builders_.size(), all_trajectory_builder_options_.size());
00184 return trajectory_id;
00185 }
00186
00187 void MapBuilder::FinishTrajectory(const int trajectory_id) {
00188 sensor_collator_->FinishTrajectory(trajectory_id);
00189 pose_graph_->FinishTrajectory(trajectory_id);
00190 }
00191
00192 std::string MapBuilder::SubmapToProto(
00193 const SubmapId& submap_id, proto::SubmapQuery::Response* const response) {
00194 if (submap_id.trajectory_id < 0 ||
00195 submap_id.trajectory_id >= num_trajectory_builders()) {
00196 return "Requested submap from trajectory " +
00197 std::to_string(submap_id.trajectory_id) + " but there are only " +
00198 std::to_string(num_trajectory_builders()) + " trajectories.";
00199 }
00200
00201 const auto submap_data = pose_graph_->GetSubmapData(submap_id);
00202 if (submap_data.submap == nullptr) {
00203 return "Requested submap " + std::to_string(submap_id.submap_index) +
00204 " from trajectory " + std::to_string(submap_id.trajectory_id) +
00205 " but it does not exist: maybe it has been trimmed.";
00206 }
00207 submap_data.submap->ToResponseProto(submap_data.pose, response);
00208 return "";
00209 }
00210
00211 void MapBuilder::SerializeState(bool include_unfinished_submaps,
00212 io::ProtoStreamWriterInterface* const writer) {
00213 io::WritePbStream(*pose_graph_, all_trajectory_builder_options_, writer,
00214 include_unfinished_submaps);
00215 }
00216
00217 bool MapBuilder::SerializeStateToFile(bool include_unfinished_submaps,
00218 const std::string& filename) {
00219 io::ProtoStreamWriter writer(filename);
00220 io::WritePbStream(*pose_graph_, all_trajectory_builder_options_, &writer,
00221 include_unfinished_submaps);
00222 return (writer.Close());
00223 }
00224
00225 std::map<int, int> MapBuilder::LoadState(
00226 io::ProtoStreamReaderInterface* const reader, bool load_frozen_state) {
00227 io::ProtoStreamDeserializer deserializer(reader);
00228
00229
00230
00231 proto::PoseGraph pose_graph_proto = deserializer.pose_graph();
00232 const auto& all_builder_options_proto =
00233 deserializer.all_trajectory_builder_options();
00234
00235 std::map<int, int> trajectory_remapping;
00236 for (int i = 0; i < pose_graph_proto.trajectory_size(); ++i) {
00237 auto& trajectory_proto = *pose_graph_proto.mutable_trajectory(i);
00238 const auto& options_with_sensor_ids_proto =
00239 all_builder_options_proto.options_with_sensor_ids(i);
00240 const int new_trajectory_id =
00241 AddTrajectoryForDeserialization(options_with_sensor_ids_proto);
00242 CHECK(trajectory_remapping
00243 .emplace(trajectory_proto.trajectory_id(), new_trajectory_id)
00244 .second)
00245 << "Duplicate trajectory ID: " << trajectory_proto.trajectory_id();
00246 trajectory_proto.set_trajectory_id(new_trajectory_id);
00247 if (load_frozen_state) {
00248 pose_graph_->FreezeTrajectory(new_trajectory_id);
00249 }
00250 }
00251
00252
00253 for (auto& constraint_proto : *pose_graph_proto.mutable_constraint()) {
00254 constraint_proto.mutable_submap_id()->set_trajectory_id(
00255 trajectory_remapping.at(constraint_proto.submap_id().trajectory_id()));
00256 constraint_proto.mutable_node_id()->set_trajectory_id(
00257 trajectory_remapping.at(constraint_proto.node_id().trajectory_id()));
00258 }
00259
00260 MapById<SubmapId, transform::Rigid3d> submap_poses;
00261 for (const proto::Trajectory& trajectory_proto :
00262 pose_graph_proto.trajectory()) {
00263 for (const proto::Trajectory::Submap& submap_proto :
00264 trajectory_proto.submap()) {
00265 submap_poses.Insert(SubmapId{trajectory_proto.trajectory_id(),
00266 submap_proto.submap_index()},
00267 transform::ToRigid3(submap_proto.pose()));
00268 }
00269 }
00270
00271 MapById<NodeId, transform::Rigid3d> node_poses;
00272 for (const proto::Trajectory& trajectory_proto :
00273 pose_graph_proto.trajectory()) {
00274 for (const proto::Trajectory::Node& node_proto : trajectory_proto.node()) {
00275 node_poses.Insert(
00276 NodeId{trajectory_proto.trajectory_id(), node_proto.node_index()},
00277 transform::ToRigid3(node_proto.pose()));
00278 }
00279 }
00280
00281
00282 for (const auto& landmark : pose_graph_proto.landmark_poses()) {
00283 pose_graph_->SetLandmarkPose(landmark.landmark_id(),
00284 transform::ToRigid3(landmark.global_pose()),
00285 true);
00286 }
00287
00288 MapById<SubmapId, mapping::proto::Submap> submap_id_to_submap;
00289 MapById<NodeId, mapping::proto::Node> node_id_to_node;
00290 SerializedData proto;
00291 while (deserializer.ReadNextSerializedData(&proto)) {
00292 switch (proto.data_case()) {
00293 case SerializedData::kPoseGraph:
00294 LOG(ERROR) << "Found multiple serialized `PoseGraph`. Serialized "
00295 "stream likely corrupt!.";
00296 break;
00297 case SerializedData::kAllTrajectoryBuilderOptions:
00298 LOG(ERROR) << "Found multiple serialized "
00299 "`AllTrajectoryBuilderOptions`. Serialized stream likely "
00300 "corrupt!.";
00301 break;
00302 case SerializedData::kSubmap: {
00303 proto.mutable_submap()->mutable_submap_id()->set_trajectory_id(
00304 trajectory_remapping.at(
00305 proto.submap().submap_id().trajectory_id()));
00306 submap_id_to_submap.Insert(
00307 SubmapId{proto.submap().submap_id().trajectory_id(),
00308 proto.submap().submap_id().submap_index()},
00309 proto.submap());
00310 break;
00311 }
00312 case SerializedData::kNode: {
00313 proto.mutable_node()->mutable_node_id()->set_trajectory_id(
00314 trajectory_remapping.at(proto.node().node_id().trajectory_id()));
00315 const NodeId node_id(proto.node().node_id().trajectory_id(),
00316 proto.node().node_id().node_index());
00317 const transform::Rigid3d& node_pose = node_poses.at(node_id);
00318 pose_graph_->AddNodeFromProto(node_pose, proto.node());
00319 node_id_to_node.Insert(node_id, proto.node());
00320 break;
00321 }
00322 case SerializedData::kTrajectoryData: {
00323 proto.mutable_trajectory_data()->set_trajectory_id(
00324 trajectory_remapping.at(proto.trajectory_data().trajectory_id()));
00325 pose_graph_->SetTrajectoryDataFromProto(proto.trajectory_data());
00326 break;
00327 }
00328 case SerializedData::kImuData: {
00329 if (load_frozen_state) break;
00330 pose_graph_->AddImuData(
00331 trajectory_remapping.at(proto.imu_data().trajectory_id()),
00332 sensor::FromProto(proto.imu_data().imu_data()));
00333 break;
00334 }
00335 case SerializedData::kOdometryData: {
00336 if (load_frozen_state) break;
00337 pose_graph_->AddOdometryData(
00338 trajectory_remapping.at(proto.odometry_data().trajectory_id()),
00339 sensor::FromProto(proto.odometry_data().odometry_data()));
00340 break;
00341 }
00342 case SerializedData::kFixedFramePoseData: {
00343 if (load_frozen_state) break;
00344 pose_graph_->AddFixedFramePoseData(
00345 trajectory_remapping.at(
00346 proto.fixed_frame_pose_data().trajectory_id()),
00347 sensor::FromProto(
00348 proto.fixed_frame_pose_data().fixed_frame_pose_data()));
00349 break;
00350 }
00351 case SerializedData::kLandmarkData: {
00352 if (load_frozen_state) break;
00353 pose_graph_->AddLandmarkData(
00354 trajectory_remapping.at(proto.landmark_data().trajectory_id()),
00355 sensor::FromProto(proto.landmark_data().landmark_data()));
00356 break;
00357 }
00358 default:
00359 LOG(WARNING) << "Skipping unknown message type in stream: "
00360 << proto.GetTypeName();
00361 }
00362 }
00363
00364
00365
00366 if (deserializer.header().format_version() ==
00367 io::kFormatVersionWithoutSubmapHistograms) {
00368 submap_id_to_submap =
00369 cartographer::io::MigrateSubmapFormatVersion1ToVersion2(
00370 submap_id_to_submap, node_id_to_node, pose_graph_proto);
00371 }
00372
00373 for (const auto& submap_id_submap : submap_id_to_submap) {
00374 pose_graph_->AddSubmapFromProto(submap_poses.at(submap_id_submap.id),
00375 submap_id_submap.data);
00376 }
00377
00378 if (load_frozen_state) {
00379
00380
00381 for (const proto::PoseGraph::Constraint& constraint_proto :
00382 pose_graph_proto.constraint()) {
00383 if (constraint_proto.tag() !=
00384 proto::PoseGraph::Constraint::INTRA_SUBMAP) {
00385 continue;
00386 }
00387 pose_graph_->AddNodeToSubmap(
00388 NodeId{constraint_proto.node_id().trajectory_id(),
00389 constraint_proto.node_id().node_index()},
00390 SubmapId{constraint_proto.submap_id().trajectory_id(),
00391 constraint_proto.submap_id().submap_index()});
00392 }
00393 } else {
00394
00395
00396
00397 pose_graph_->AddSerializedConstraints(
00398 FromProto(pose_graph_proto.constraint()));
00399 }
00400 CHECK(reader->eof());
00401 return trajectory_remapping;
00402 }
00403
00404 std::map<int, int> MapBuilder::LoadStateFromFile(
00405 const std::string& state_filename, const bool load_frozen_state) {
00406 const std::string suffix = ".pbstream";
00407 if (state_filename.substr(
00408 std::max<int>(state_filename.size() - suffix.size(), 0)) != suffix) {
00409 LOG(WARNING) << "The file containing the state should be a "
00410 ".pbstream file.";
00411 }
00412 LOG(INFO) << "Loading saved state '" << state_filename << "'...";
00413 io::ProtoStreamReader stream(state_filename);
00414 return LoadState(&stream, load_frozen_state);
00415 }
00416
00417 }
00418 }