21 #include "cartographer/mapping_2d/range_data_inserter.h" 23 #include "glog/logging.h" 27 Eigen::AlignedBox2f ComputeMapBoundingBox(
28 const std::vector<::cartographer::mapping::TrajectoryNode>&
30 Eigen::AlignedBox2f bounding_box(Eigen::Vector2f::Zero());
31 for (
const auto& node : trajectory_nodes) {
35 const auto& data = *node.constant_data;
37 if (!data.range_data_3d.returns.empty()) {
38 range_data = ::cartographer::sensor::TransformRangeData(
40 node.pose.cast<
float>());
42 range_data = ::cartographer::sensor::TransformRangeData(
43 data.range_data_2d, node.pose.cast<
float>());
45 bounding_box.extend(range_data.
origin.head<2>());
46 for (
const Eigen::Vector3f& hit : range_data.
returns) {
47 bounding_box.extend(hit.head<2>());
49 for (
const Eigen::Vector3f& miss : range_data.
misses) {
50 bounding_box.extend(miss.head<2>());
61 const std::vector<::cartographer::mapping::TrajectoryNode>&
63 const string& map_frame,
64 const ::cartographer::mapping_2d::proto::SubmapsOptions& submaps_options,
65 ::nav_msgs::OccupancyGrid*
const occupancy_grid) {
66 CHECK(!trajectory_nodes.empty());
67 namespace carto = ::cartographer;
68 const carto::mapping_2d::MapLimits map_limits =
70 carto::mapping_2d::ProbabilityGrid probability_grid(map_limits);
71 carto::mapping_2d::RangeDataInserter range_data_inserter(
72 submaps_options.range_data_inserter_options());
73 for (
const auto& node : trajectory_nodes) {
77 CHECK(node.constant_data->range_data_3d.returns.empty());
78 range_data_inserter.Insert(
79 carto::sensor::TransformRangeData(node.constant_data->range_data_2d,
80 node.pose.cast<
float>()),
85 occupancy_grid->header.stamp =
ToRos(trajectory_nodes.back().time());
86 occupancy_grid->header.frame_id = map_frame;
87 occupancy_grid->info.map_load_time = occupancy_grid->header.stamp;
89 Eigen::Array2i offset;
90 carto::mapping_2d::CellLimits cell_limits;
91 probability_grid.ComputeCroppedLimits(&offset, &cell_limits);
92 const double resolution = probability_grid.limits().resolution();
94 occupancy_grid->info.resolution = resolution;
95 occupancy_grid->info.width = cell_limits.num_y_cells;
96 occupancy_grid->info.height = cell_limits.num_x_cells;
98 occupancy_grid->info.origin.position.x =
99 probability_grid.limits().max().x() -
100 (offset.y() + cell_limits.num_y_cells) * resolution;
101 occupancy_grid->info.origin.position.y =
102 probability_grid.limits().max().y() -
103 (offset.x() + cell_limits.num_x_cells) * resolution;
104 occupancy_grid->info.origin.position.z = 0.;
105 occupancy_grid->info.origin.orientation.w = 1.;
106 occupancy_grid->info.origin.orientation.x = 0.;
107 occupancy_grid->info.origin.orientation.y = 0.;
108 occupancy_grid->info.origin.orientation.z = 0.;
110 occupancy_grid->data.resize(cell_limits.num_x_cells * cell_limits.num_y_cells,
112 for (
const Eigen::Array2i& xy_index :
113 carto::mapping_2d::XYIndexRangeIterator(cell_limits)) {
114 if (probability_grid.IsKnown(xy_index + offset)) {
115 const int value = carto::common::RoundToInt(
116 (probability_grid.GetProbability(xy_index + offset) -
117 carto::mapping::kMinProbability) *
119 (carto::mapping::kMaxProbability - carto::mapping::kMinProbability));
121 CHECK_GE(100, value);
122 occupancy_grid->data[(cell_limits.num_x_cells - xy_index.x()) *
123 cell_limits.num_y_cells -
124 xy_index.y() - 1] = value;
130 const double resolution,
131 const std::vector<::cartographer::mapping::TrajectoryNode>&
133 Eigen::AlignedBox2f bounding_box = ComputeMapBoundingBox(trajectory_nodes);
136 const float kPadding = 3.f * resolution;
137 bounding_box.min() -= kPadding * Eigen::Vector2f::Ones();
138 bounding_box.max() += kPadding * Eigen::Vector2f::Ones();
139 const Eigen::Vector2d pixel_sizes =
140 bounding_box.sizes().cast<
double>() / resolution;
141 return ::cartographer::mapping_2d::MapLimits(
142 resolution, bounding_box.max().cast<
double>(),
int RoundToInt(const float x)
RangeData Decompress(const CompressedRangeData &compressed_range_data)
void BuildOccupancyGrid2D(const std::vector<::cartographer::mapping::TrajectoryNode > &trajectory_nodes, const string &map_frame, const ::cartographer::mapping_2d::proto::SubmapsOptions &submaps_options,::nav_msgs::OccupancyGrid *const occupancy_grid)
::cartographer::mapping_2d::MapLimits ComputeMapLimits(const double resolution, const std::vector<::cartographer::mapping::TrajectoryNode > &trajectory_nodes)
::ros::Time ToRos(::cartographer::common::Time time)