28 #include "cartographer/mapping/proto/pose_graph.pb.h" 29 #include "cartographer/mapping/proto/serialization.pb.h" 30 #include "cartographer/mapping/proto/submap.pb.h" 31 #include "cartographer/mapping/proto/trajectory_builder_options.pb.h" 37 #include "gflags/gflags.h" 38 #include "glog/logging.h" 39 #include "nav_msgs/OccupancyGrid.h" 43 "Filename of a pbstream to draw a map from.");
44 DEFINE_string(map_topic,
"map",
"Name of the published map topic.");
45 DEFINE_string(map_frame_id,
"map",
"Frame ID of the published map.");
46 DEFINE_double(resolution, 0.05,
"Resolution of a grid cell in the drawn map.");
51 void Run(
const std::string& pbstream_filename,
const std::string& map_topic,
52 const std::string& map_frame_id,
const double resolution) {
56 LOG(INFO) <<
"Loading submap slices from serialized data.";
57 std::map<::cartographer::mapping::SubmapId, ::cartographer::io::SubmapSlice>
59 ::cartographer::mapping::proto::SerializedData proto;
60 while (deserializer.ReadNextSerializedData(&proto)) {
61 if (proto.has_submap()) {
62 const auto& submap = proto.submap();
63 const ::cartographer::mapping::SubmapId
id{
64 submap.submap_id().trajectory_id(),
65 submap.submap_id().submap_index()};
66 const ::cartographer::transform::Rigid3d global_submap_pose =
67 ::cartographer::transform::ToRigid3(deserializer.pose_graph()
68 .trajectory(
id.trajectory_id)
69 .submap(
id.submap_index)
80 LOG(INFO) <<
"Generating combined map image from submap slices.";
81 const auto painted_slices =
82 ::cartographer::io::PaintSubmapSlices(submap_slices, resolution);
86 LOG(INFO) <<
"Publishing occupancy grid topic " << map_topic
87 <<
" (frame_id: " << map_frame_id
88 <<
", resolution:" << std::to_string(resolution) <<
").";
97 int main(
int argc,
char** argv) {
98 FLAGS_alsologtostderr =
true;
99 google::InitGoogleLogging(argv[0]);
100 google::ParseCommandLineFlags(&argc, &argv,
true);
102 CHECK(!FLAGS_pbstream_filename.empty()) <<
"-pbstream_filename is missing.";
104 ::ros::init(argc, argv,
"cartographer_pbstream_map_publisher");
109 ::cartographer_ros::Run(FLAGS_pbstream_filename, FLAGS_map_topic,
110 FLAGS_map_frame_id, FLAGS_resolution);
std::unique_ptr< nav_msgs::OccupancyGrid > CreateOccupancyGridMsg(const cartographer::io::PaintSubmapSlicesResult &painted_slices, const double resolution, const std::string &frame_id, const ros::Time &time)
constexpr int kLatestOnlyPublisherQueueSize
DEFINE_string(pbstream_filename, "", "Filename of a pbstream to draw a map from.")
void publish(const boost::shared_ptr< M > &message) const
void FillSubmapSlice(const ::cartographer::transform::Rigid3d &global_submap_pose, const ::cartographer::mapping::proto::Submap &proto, SubmapSlice *const submap_slice)
DEFINE_double(resolution, 0.05, "Resolution of a grid cell in the drawn map.")
int main(int argc, char **argv)
void Run(const std::string &configuration_directory, const std::string &configuration_basename)