occupancy_grid.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2016 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
18 
21 #include "cartographer/mapping_2d/range_data_inserter.h"
23 #include "glog/logging.h"
24 
25 namespace {
26 
27 Eigen::AlignedBox2f ComputeMapBoundingBox(
28  const std::vector<::cartographer::mapping::TrajectoryNode>&
29  trajectory_nodes) {
30  Eigen::AlignedBox2f bounding_box(Eigen::Vector2f::Zero());
31  for (const auto& node : trajectory_nodes) {
32  if (node.trimmed()) {
33  continue;
34  }
35  const auto& data = *node.constant_data;
37  if (!data.range_data_3d.returns.empty()) {
38  range_data = ::cartographer::sensor::TransformRangeData(
39  ::cartographer::sensor::Decompress(data.range_data_3d),
40  node.pose.cast<float>());
41  } else {
42  range_data = ::cartographer::sensor::TransformRangeData(
43  data.range_data_2d, node.pose.cast<float>());
44  }
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>());
48  }
49  for (const Eigen::Vector3f& miss : range_data.misses) {
50  bounding_box.extend(miss.head<2>());
51  }
52  }
53  return bounding_box;
54 }
55 
56 } // namespace
57 
58 namespace cartographer_ros {
59 
61  const std::vector<::cartographer::mapping::TrajectoryNode>&
62  trajectory_nodes,
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 =
69  ComputeMapLimits(submaps_options.resolution(), trajectory_nodes);
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) {
74  if (node.trimmed()) {
75  continue;
76  }
77  CHECK(node.constant_data->range_data_3d.returns.empty()); // No 3D yet.
78  range_data_inserter.Insert(
79  carto::sensor::TransformRangeData(node.constant_data->range_data_2d,
80  node.pose.cast<float>()),
81  &probability_grid);
82  }
83 
84  // TODO(whess): Compute the latest time of in 'trajectory_nodes'.
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;
88 
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();
93 
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;
97 
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.;
109 
110  occupancy_grid->data.resize(cell_limits.num_x_cells * cell_limits.num_y_cells,
111  -1);
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) *
118  100. /
119  (carto::mapping::kMaxProbability - carto::mapping::kMinProbability));
120  CHECK_LE(0, value);
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;
125  }
126  }
127 }
128 
130  const double resolution,
131  const std::vector<::cartographer::mapping::TrajectoryNode>&
132  trajectory_nodes) {
133  Eigen::AlignedBox2f bounding_box = ComputeMapBoundingBox(trajectory_nodes);
134  // Add some padding to ensure all rays are still contained in the map after
135  // discretization.
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>(),
144  ::cartographer::common::RoundToInt(pixel_sizes.y()),
145  ::cartographer::common::RoundToInt(pixel_sizes.x())));
146 }
147 
148 } // namespace cartographer_ros
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)
float value
::ros::Time ToRos(::cartographer::common::Time time)


cartographer_ros
Author(s):
autogenerated on Wed Jun 5 2019 22:35:56