Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include "cartographer_ros/assets_writer.h"
00018
00019 #include <algorithm>
00020 #include <fstream>
00021 #include <iostream>
00022
00023 #include "absl/memory/memory.h"
00024 #include "cartographer/common/configuration_file_resolver.h"
00025 #include "cartographer/common/math.h"
00026 #include "cartographer/io/file_writer.h"
00027 #include "cartographer/io/points_processor.h"
00028 #include "cartographer/io/points_processor_pipeline_builder.h"
00029 #include "cartographer/io/proto_stream.h"
00030 #include "cartographer/io/proto_stream_deserializer.h"
00031 #include "cartographer/mapping/proto/pose_graph.pb.h"
00032 #include "cartographer/mapping/proto/trajectory_builder_options.pb.h"
00033 #include "cartographer/sensor/point_cloud.h"
00034 #include "cartographer/sensor/range_data.h"
00035 #include "cartographer/transform/transform_interpolation_buffer.h"
00036 #include "cartographer_ros/msg_conversion.h"
00037 #include "cartographer_ros/ros_map_writing_points_processor.h"
00038 #include "cartographer_ros/time_conversion.h"
00039 #include "cartographer_ros/urdf_reader.h"
00040 #include "gflags/gflags.h"
00041 #include "glog/logging.h"
00042 #include "ros/ros.h"
00043 #include "ros/time.h"
00044 #include "rosbag/bag.h"
00045 #include "rosbag/view.h"
00046 #include "tf2_eigen/tf2_eigen.h"
00047 #include "tf2_msgs/TFMessage.h"
00048 #include "tf2_ros/buffer.h"
00049 #include "urdf/model.h"
00050
00051 namespace cartographer_ros {
00052 namespace {
00053
00054 constexpr char kTfStaticTopic[] = "/tf_static";
00055 namespace carto = ::cartographer;
00056
00057 std::unique_ptr<carto::io::PointsProcessorPipelineBuilder>
00058 CreatePipelineBuilder(
00059 const std::vector<carto::mapping::proto::Trajectory>& trajectories,
00060 const std::string file_prefix) {
00061 const auto file_writer_factory =
00062 AssetsWriter::CreateFileWriterFactory(file_prefix);
00063 auto builder = absl::make_unique<carto::io::PointsProcessorPipelineBuilder>();
00064 carto::io::RegisterBuiltInPointsProcessors(trajectories, file_writer_factory,
00065 builder.get());
00066 builder->Register(RosMapWritingPointsProcessor::kConfigurationFileActionName,
00067 [file_writer_factory](
00068 carto::common::LuaParameterDictionary* const dictionary,
00069 carto::io::PointsProcessor* const next)
00070 -> std::unique_ptr<carto::io::PointsProcessor> {
00071 return RosMapWritingPointsProcessor::FromDictionary(
00072 file_writer_factory, dictionary, next);
00073 });
00074 return builder;
00075 }
00076
00077 std::unique_ptr<carto::common::LuaParameterDictionary> LoadLuaDictionary(
00078 const std::string& configuration_directory,
00079 const std::string& configuration_basename) {
00080 auto file_resolver =
00081 absl::make_unique<carto::common::ConfigurationFileResolver>(
00082 std::vector<std::string>{configuration_directory});
00083
00084 const std::string code =
00085 file_resolver->GetFileContentOrDie(configuration_basename);
00086 auto lua_parameter_dictionary =
00087 absl::make_unique<carto::common::LuaParameterDictionary>(
00088 code, std::move(file_resolver));
00089 return lua_parameter_dictionary;
00090 }
00091
00092 template <typename T>
00093 std::unique_ptr<carto::io::PointsBatch> HandleMessage(
00094 const T& message, const std::string& tracking_frame,
00095 const tf2_ros::Buffer& tf_buffer,
00096 const carto::transform::TransformInterpolationBuffer&
00097 transform_interpolation_buffer) {
00098 const carto::common::Time start_time = FromRos(message.header.stamp);
00099
00100 auto points_batch = absl::make_unique<carto::io::PointsBatch>();
00101 points_batch->start_time = start_time;
00102 points_batch->frame_id = message.header.frame_id;
00103
00104 carto::sensor::PointCloudWithIntensities point_cloud;
00105 carto::common::Time point_cloud_time;
00106 std::tie(point_cloud, point_cloud_time) =
00107 ToPointCloudWithIntensities(message);
00108 CHECK_EQ(point_cloud.intensities.size(), point_cloud.points.size());
00109
00110 for (size_t i = 0; i < point_cloud.points.size(); ++i) {
00111 const carto::common::Time time =
00112 point_cloud_time +
00113 carto::common::FromSeconds(point_cloud.points[i].time);
00114 if (!transform_interpolation_buffer.Has(time)) {
00115 continue;
00116 }
00117 const carto::transform::Rigid3d tracking_to_map =
00118 transform_interpolation_buffer.Lookup(time);
00119 const carto::transform::Rigid3d sensor_to_tracking =
00120 ToRigid3d(tf_buffer.lookupTransform(
00121 tracking_frame, message.header.frame_id, ToRos(time)));
00122 const carto::transform::Rigid3f sensor_to_map =
00123 (tracking_to_map * sensor_to_tracking).cast<float>();
00124 points_batch->points.push_back(
00125 sensor_to_map *
00126 carto::sensor::ToRangefinderPoint(point_cloud.points[i]));
00127 points_batch->intensities.push_back(point_cloud.intensities[i]);
00128
00129 points_batch->origin = sensor_to_map * Eigen::Vector3f::Zero();
00130 }
00131 if (points_batch->points.empty()) {
00132 return nullptr;
00133 }
00134 return points_batch;
00135 }
00136
00137 }
00138
00139 AssetsWriter::AssetsWriter(const std::string& pose_graph_filename,
00140 const std::vector<std::string>& bag_filenames,
00141 const std::string& output_file_prefix)
00142 : bag_filenames_(bag_filenames),
00143 pose_graph_(
00144 carto::io::DeserializePoseGraphFromFile(pose_graph_filename)) {
00145 CHECK_EQ(pose_graph_.trajectory_size(), bag_filenames_.size())
00146 << "Pose graphs contains " << pose_graph_.trajectory_size()
00147 << " trajectories while " << bag_filenames_.size()
00148 << " bags were provided. This tool requires one bag for each "
00149 "trajectory in the same order as the correponding trajectories in the "
00150 "pose graph proto.";
00151
00152
00153 all_trajectories_ = std::vector<::cartographer::mapping::proto::Trajectory>(
00154 pose_graph_.trajectory().begin(), pose_graph_.trajectory().end());
00155
00156 const std::string file_prefix = !output_file_prefix.empty()
00157 ? output_file_prefix
00158 : bag_filenames_.front() + "_";
00159 point_pipeline_builder_ =
00160 CreatePipelineBuilder(all_trajectories_, file_prefix);
00161 }
00162
00163 void AssetsWriter::RegisterPointsProcessor(
00164 const std::string& name,
00165 cartographer::io::PointsProcessorPipelineBuilder::FactoryFunction factory) {
00166 point_pipeline_builder_->Register(name, factory);
00167 }
00168
00169 void AssetsWriter::Run(const std::string& configuration_directory,
00170 const std::string& configuration_basename,
00171 const std::string& urdf_filename,
00172 const bool use_bag_transforms) {
00173 const auto lua_parameter_dictionary =
00174 LoadLuaDictionary(configuration_directory, configuration_basename);
00175
00176 std::vector<std::unique_ptr<carto::io::PointsProcessor>> pipeline =
00177 point_pipeline_builder_->CreatePipeline(
00178 lua_parameter_dictionary->GetDictionary("pipeline").get());
00179 const std::string tracking_frame =
00180 lua_parameter_dictionary->GetString("tracking_frame");
00181
00182 do {
00183 for (size_t trajectory_id = 0; trajectory_id < bag_filenames_.size();
00184 ++trajectory_id) {
00185 const carto::mapping::proto::Trajectory& trajectory_proto =
00186 pose_graph_.trajectory(trajectory_id);
00187 const std::string& bag_filename = bag_filenames_[trajectory_id];
00188 LOG(INFO) << "Processing " << bag_filename << "...";
00189 if (trajectory_proto.node_size() == 0) {
00190 continue;
00191 }
00192 tf2_ros::Buffer tf_buffer;
00193 if (!urdf_filename.empty()) {
00194 ReadStaticTransformsFromUrdf(urdf_filename, &tf_buffer);
00195 }
00196
00197 const carto::transform::TransformInterpolationBuffer
00198 transform_interpolation_buffer(trajectory_proto);
00199 rosbag::Bag bag;
00200 bag.open(bag_filename, rosbag::bagmode::Read);
00201 rosbag::View view(bag);
00202 const ::ros::Time begin_time = view.getBeginTime();
00203 const double duration_in_seconds =
00204 (view.getEndTime() - begin_time).toSec();
00205
00206
00207
00208
00209 std::deque<rosbag::MessageInstance> delayed_messages;
00210
00211
00212
00213 const ::ros::Duration kDelay(1.);
00214 for (const rosbag::MessageInstance& message : view) {
00215 if (use_bag_transforms && message.isType<tf2_msgs::TFMessage>()) {
00216 auto tf_message = message.instantiate<tf2_msgs::TFMessage>();
00217 for (const auto& transform : tf_message->transforms) {
00218 try {
00219 tf_buffer.setTransform(transform, "unused_authority",
00220 message.getTopic() == kTfStaticTopic);
00221 } catch (const tf2::TransformException& ex) {
00222 LOG(WARNING) << ex.what();
00223 }
00224 }
00225 }
00226
00227 while (!delayed_messages.empty() && delayed_messages.front().getTime() <
00228 message.getTime() - kDelay) {
00229 const rosbag::MessageInstance& delayed_message =
00230 delayed_messages.front();
00231
00232 std::unique_ptr<carto::io::PointsBatch> points_batch;
00233 if (delayed_message.isType<sensor_msgs::PointCloud2>()) {
00234 points_batch = HandleMessage(
00235 *delayed_message.instantiate<sensor_msgs::PointCloud2>(),
00236 tracking_frame, tf_buffer, transform_interpolation_buffer);
00237 } else if (delayed_message
00238 .isType<sensor_msgs::MultiEchoLaserScan>()) {
00239 points_batch = HandleMessage(
00240 *delayed_message.instantiate<sensor_msgs::MultiEchoLaserScan>(),
00241 tracking_frame, tf_buffer, transform_interpolation_buffer);
00242 } else if (delayed_message.isType<sensor_msgs::LaserScan>()) {
00243 points_batch = HandleMessage(
00244 *delayed_message.instantiate<sensor_msgs::LaserScan>(),
00245 tracking_frame, tf_buffer, transform_interpolation_buffer);
00246 }
00247 if (points_batch != nullptr) {
00248 points_batch->trajectory_id = trajectory_id;
00249 pipeline.back()->Process(std::move(points_batch));
00250 }
00251 delayed_messages.pop_front();
00252 }
00253 delayed_messages.push_back(message);
00254 LOG_EVERY_N(INFO, 10000)
00255 << "Processed " << (message.getTime() - begin_time).toSec()
00256 << " of " << duration_in_seconds << " bag time seconds...";
00257 }
00258 bag.close();
00259 }
00260 } while (pipeline.back()->Flush() ==
00261 carto::io::PointsProcessor::FlushResult::kRestartStream);
00262 }
00263
00264 ::cartographer::io::FileWriterFactory AssetsWriter::CreateFileWriterFactory(
00265 const std::string& file_path) {
00266 const auto file_writer_factory = [file_path](const std::string& filename) {
00267 return absl::make_unique<carto::io::StreamFileWriter>(file_path + filename);
00268 };
00269 return file_writer_factory;
00270 }
00271
00272 }