probability_grid.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 #include "cartographer/mapping/2d/probability_grid.h"
00017 
00018 #include <limits>
00019 
00020 #include "absl/memory/memory.h"
00021 #include "cartographer/mapping/probability_values.h"
00022 #include "cartographer/mapping/submaps.h"
00023 
00024 namespace cartographer {
00025 namespace mapping {
00026 
00027 ProbabilityGrid::ProbabilityGrid(const MapLimits& limits,
00028                                  ValueConversionTables* conversion_tables)
00029     : Grid2D(limits, kMinCorrespondenceCost, kMaxCorrespondenceCost,
00030              conversion_tables),
00031       conversion_tables_(conversion_tables) {}
00032 
00033 ProbabilityGrid::ProbabilityGrid(const proto::Grid2D& proto,
00034                                  ValueConversionTables* conversion_tables)
00035     : Grid2D(proto, conversion_tables), conversion_tables_(conversion_tables) {
00036   CHECK(proto.has_probability_grid_2d());
00037 }
00038 
00039 // Sets the probability of the cell at 'cell_index' to the given
00040 // 'probability'. Only allowed if the cell was unknown before.
00041 void ProbabilityGrid::SetProbability(const Eigen::Array2i& cell_index,
00042                                      const float probability) {
00043   uint16& cell =
00044       (*mutable_correspondence_cost_cells())[ToFlatIndex(cell_index)];
00045   CHECK_EQ(cell, kUnknownProbabilityValue);
00046   cell =
00047       CorrespondenceCostToValue(ProbabilityToCorrespondenceCost(probability));
00048   mutable_known_cells_box()->extend(cell_index.matrix());
00049 }
00050 
00051 // Applies the 'odds' specified when calling ComputeLookupTableToApplyOdds()
00052 // to the probability of the cell at 'cell_index' if the cell has not already
00053 // been updated. Multiple updates of the same cell will be ignored until
00054 // FinishUpdate() is called. Returns true if the cell was updated.
00055 //
00056 // If this is the first call to ApplyOdds() for the specified cell, its value
00057 // will be set to probability corresponding to 'odds'.
00058 bool ProbabilityGrid::ApplyLookupTable(const Eigen::Array2i& cell_index,
00059                                        const std::vector<uint16>& table) {
00060   DCHECK_EQ(table.size(), kUpdateMarker);
00061   const int flat_index = ToFlatIndex(cell_index);
00062   uint16* cell = &(*mutable_correspondence_cost_cells())[flat_index];
00063   if (*cell >= kUpdateMarker) {
00064     return false;
00065   }
00066   mutable_update_indices()->push_back(flat_index);
00067   *cell = table[*cell];
00068   DCHECK_GE(*cell, kUpdateMarker);
00069   mutable_known_cells_box()->extend(cell_index.matrix());
00070   return true;
00071 }
00072 
00073 GridType ProbabilityGrid::GetGridType() const {
00074   return GridType::PROBABILITY_GRID;
00075 }
00076 
00077 // Returns the probability of the cell with 'cell_index'.
00078 float ProbabilityGrid::GetProbability(const Eigen::Array2i& cell_index) const {
00079   if (!limits().Contains(cell_index)) return kMinProbability;
00080   return CorrespondenceCostToProbability(ValueToCorrespondenceCost(
00081       correspondence_cost_cells()[ToFlatIndex(cell_index)]));
00082 }
00083 
00084 proto::Grid2D ProbabilityGrid::ToProto() const {
00085   proto::Grid2D result;
00086   result = Grid2D::ToProto();
00087   result.mutable_probability_grid_2d();
00088   return result;
00089 }
00090 
00091 std::unique_ptr<Grid2D> ProbabilityGrid::ComputeCroppedGrid() const {
00092   Eigen::Array2i offset;
00093   CellLimits cell_limits;
00094   ComputeCroppedLimits(&offset, &cell_limits);
00095   const double resolution = limits().resolution();
00096   const Eigen::Vector2d max =
00097       limits().max() - resolution * Eigen::Vector2d(offset.y(), offset.x());
00098   std::unique_ptr<ProbabilityGrid> cropped_grid =
00099       absl::make_unique<ProbabilityGrid>(
00100           MapLimits(resolution, max, cell_limits), conversion_tables_);
00101   for (const Eigen::Array2i& xy_index : XYIndexRangeIterator(cell_limits)) {
00102     if (!IsKnown(xy_index + offset)) continue;
00103     cropped_grid->SetProbability(xy_index, GetProbability(xy_index + offset));
00104   }
00105 
00106   return std::unique_ptr<Grid2D>(cropped_grid.release());
00107 }
00108 
00109 bool ProbabilityGrid::DrawToSubmapTexture(
00110     proto::SubmapQuery::Response::SubmapTexture* const texture,
00111     transform::Rigid3d local_pose) const {
00112   Eigen::Array2i offset;
00113   CellLimits cell_limits;
00114   ComputeCroppedLimits(&offset, &cell_limits);
00115 
00116   std::string cells;
00117   for (const Eigen::Array2i& xy_index : XYIndexRangeIterator(cell_limits)) {
00118     if (!IsKnown(xy_index + offset)) {
00119       cells.push_back(0 /* unknown log odds value */);
00120       cells.push_back(0 /* alpha */);
00121       continue;
00122     }
00123     // We would like to add 'delta' but this is not possible using a value and
00124     // alpha. We use premultiplied alpha, so when 'delta' is positive we can
00125     // add it by setting 'alpha' to zero. If it is negative, we set 'value' to
00126     // zero, and use 'alpha' to subtract. This is only correct when the pixel
00127     // is currently white, so walls will look too gray. This should be hard to
00128     // detect visually for the user, though.
00129     const int delta =
00130         128 - ProbabilityToLogOddsInteger(GetProbability(xy_index + offset));
00131     const uint8 alpha = delta > 0 ? 0 : -delta;
00132     const uint8 value = delta > 0 ? delta : 0;
00133     cells.push_back(value);
00134     cells.push_back((value || alpha) ? alpha : 1);
00135   }
00136 
00137   common::FastGzipString(cells, texture->mutable_cells());
00138   texture->set_width(cell_limits.num_x_cells);
00139   texture->set_height(cell_limits.num_y_cells);
00140   const double resolution = limits().resolution();
00141   texture->set_resolution(resolution);
00142   const double max_x = limits().max().x() - resolution * offset.y();
00143   const double max_y = limits().max().y() - resolution * offset.x();
00144   *texture->mutable_slice_pose() = transform::ToProto(
00145       local_pose.inverse() *
00146       transform::Rigid3d::Translation(Eigen::Vector3d(max_x, max_y, 0.)));
00147 
00148   return true;
00149 }
00150 
00151 }  // namespace mapping
00152 }  // namespace cartographer


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35