tsdf_2d.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2018 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 
00017 #include "cartographer/mapping/2d/tsdf_2d.h"
00018 
00019 #include "absl/memory/memory.h"
00020 
00021 namespace cartographer {
00022 namespace mapping {
00023 
00024 TSDF2D::TSDF2D(const MapLimits& limits, float truncation_distance,
00025                float max_weight, ValueConversionTables* conversion_tables)
00026     : Grid2D(limits, -truncation_distance, truncation_distance,
00027              conversion_tables),
00028       conversion_tables_(conversion_tables),
00029       value_converter_(absl::make_unique<TSDValueConverter>(
00030           truncation_distance, max_weight, conversion_tables_)),
00031       weight_cells_(
00032           limits.cell_limits().num_x_cells * limits.cell_limits().num_y_cells,
00033           value_converter_->getUnknownWeightValue()) {}
00034 
00035 TSDF2D::TSDF2D(const proto::Grid2D& proto,
00036                ValueConversionTables* conversion_tables)
00037     : Grid2D(proto, conversion_tables), conversion_tables_(conversion_tables) {
00038   CHECK(proto.has_tsdf_2d());
00039   value_converter_ = absl::make_unique<TSDValueConverter>(
00040       proto.tsdf_2d().truncation_distance(), proto.tsdf_2d().max_weight(),
00041       conversion_tables_);
00042   weight_cells_.reserve(proto.tsdf_2d().weight_cells_size());
00043   for (const auto& cell : proto.tsdf_2d().weight_cells()) {
00044     CHECK_LE(cell, std::numeric_limits<uint16>::max());
00045     weight_cells_.push_back(cell);
00046   }
00047 }
00048 
00049 bool TSDF2D::CellIsUpdated(const Eigen::Array2i& cell_index) const {
00050   const int flat_index = ToFlatIndex(cell_index);
00051   uint16 tsdf_cell = correspondence_cost_cells()[flat_index];
00052   return tsdf_cell >= value_converter_->getUpdateMarker();
00053 }
00054 
00055 void TSDF2D::SetCell(const Eigen::Array2i& cell_index, float tsd,
00056                      float weight) {
00057   const int flat_index = ToFlatIndex(cell_index);
00058   uint16* tsdf_cell = &(*mutable_correspondence_cost_cells())[flat_index];
00059   if (*tsdf_cell >= value_converter_->getUpdateMarker()) {
00060     return;
00061   }
00062   mutable_update_indices()->push_back(flat_index);
00063   mutable_known_cells_box()->extend(cell_index.matrix());
00064   *tsdf_cell =
00065       value_converter_->TSDToValue(tsd) + value_converter_->getUpdateMarker();
00066   uint16* weight_cell = &weight_cells_[flat_index];
00067   *weight_cell = value_converter_->WeightToValue(weight);
00068 }
00069 
00070 GridType TSDF2D::GetGridType() const { return GridType::TSDF; }
00071 
00072 float TSDF2D::GetTSD(const Eigen::Array2i& cell_index) const {
00073   if (limits().Contains(cell_index)) {
00074     return value_converter_->ValueToTSD(
00075         correspondence_cost_cells()[ToFlatIndex(cell_index)]);
00076   }
00077   return value_converter_->getMinTSD();
00078 }
00079 
00080 float TSDF2D::GetWeight(const Eigen::Array2i& cell_index) const {
00081   if (limits().Contains(cell_index)) {
00082     return value_converter_->ValueToWeight(
00083         weight_cells_[ToFlatIndex(cell_index)]);
00084   }
00085   return value_converter_->getMinWeight();
00086 }
00087 
00088 std::pair<float, float> TSDF2D::GetTSDAndWeight(
00089     const Eigen::Array2i& cell_index) const {
00090   if (limits().Contains(cell_index)) {
00091     int flat_index = ToFlatIndex(cell_index);
00092     return std::make_pair(
00093         value_converter_->ValueToTSD(correspondence_cost_cells()[flat_index]),
00094         value_converter_->ValueToWeight(weight_cells_[flat_index]));
00095   }
00096   return std::make_pair(value_converter_->getMinTSD(),
00097                         value_converter_->getMinWeight());
00098 }
00099 
00100 void TSDF2D::GrowLimits(const Eigen::Vector2f& point) {
00101   Grid2D::GrowLimits(point,
00102                      {mutable_correspondence_cost_cells(), &weight_cells_},
00103                      {value_converter_->getUnknownTSDValue(),
00104                       value_converter_->getUnknownWeightValue()});
00105 }
00106 
00107 proto::Grid2D TSDF2D::ToProto() const {
00108   proto::Grid2D result;
00109   result = Grid2D::ToProto();
00110   *result.mutable_tsdf_2d()->mutable_weight_cells() = {weight_cells_.begin(),
00111                                                        weight_cells_.end()};
00112   result.mutable_tsdf_2d()->set_truncation_distance(
00113       value_converter_->getMaxTSD());
00114   result.mutable_tsdf_2d()->set_max_weight(value_converter_->getMaxWeight());
00115   return result;
00116 }
00117 
00118 std::unique_ptr<Grid2D> TSDF2D::ComputeCroppedGrid() const {
00119   Eigen::Array2i offset;
00120   CellLimits cell_limits;
00121   ComputeCroppedLimits(&offset, &cell_limits);
00122   const double resolution = limits().resolution();
00123   const Eigen::Vector2d max =
00124       limits().max() - resolution * Eigen::Vector2d(offset.y(), offset.x());
00125   std::unique_ptr<TSDF2D> cropped_grid = absl::make_unique<TSDF2D>(
00126       MapLimits(resolution, max, cell_limits), value_converter_->getMaxTSD(),
00127       value_converter_->getMaxWeight(), conversion_tables_);
00128   for (const Eigen::Array2i& xy_index : XYIndexRangeIterator(cell_limits)) {
00129     if (!IsKnown(xy_index + offset)) continue;
00130     cropped_grid->SetCell(xy_index, GetTSD(xy_index + offset),
00131                           GetWeight(xy_index + offset));
00132   }
00133   cropped_grid->FinishUpdate();
00134   return std::move(cropped_grid);
00135 }
00136 
00137 bool TSDF2D::DrawToSubmapTexture(
00138     proto::SubmapQuery::Response::SubmapTexture* const texture,
00139     transform::Rigid3d local_pose) const {
00140   Eigen::Array2i offset;
00141   CellLimits cell_limits;
00142   ComputeCroppedLimits(&offset, &cell_limits);
00143 
00144   std::string cells;
00145   for (const Eigen::Array2i& xy_index : XYIndexRangeIterator(cell_limits)) {
00146     if (!IsKnown(xy_index + offset)) {
00147       cells.push_back(0);  // value
00148       cells.push_back(0);  // alpha
00149       continue;
00150     }
00151     // We would like to add 'delta' but this is not possible using a value and
00152     // alpha. We use premultiplied alpha, so when 'delta' is positive we can
00153     // add it by setting 'alpha' to zero. If it is negative, we set 'value' to
00154     // zero, and use 'alpha' to subtract. This is only correct when the pixel
00155     // is currently white, so walls will look too gray. This should be hard to
00156     // detect visually for the user, though.
00157     float normalized_tsdf = std::abs(GetTSD(xy_index + offset));
00158     normalized_tsdf =
00159         std::pow(normalized_tsdf / value_converter_->getMaxTSD(), 0.5f);
00160     float normalized_weight =
00161         GetWeight(xy_index + offset) / value_converter_->getMaxWeight();
00162     const int delta = static_cast<int>(
00163         std::round(normalized_weight * (normalized_tsdf * 255. - 128.)));
00164     const uint8 alpha = delta > 0 ? 0 : -delta;
00165     const uint8 value = delta > 0 ? delta : 0;
00166     cells.push_back(value);
00167     cells.push_back((value || alpha) ? alpha : 1);
00168   }
00169 
00170   common::FastGzipString(cells, texture->mutable_cells());
00171   texture->set_width(cell_limits.num_x_cells);
00172   texture->set_height(cell_limits.num_y_cells);
00173   const double resolution = limits().resolution();
00174   texture->set_resolution(resolution);
00175   const double max_x = limits().max().x() - resolution * offset.y();
00176   const double max_y = limits().max().y() - resolution * offset.x();
00177   *texture->mutable_slice_pose() = transform::ToProto(
00178       local_pose.inverse() *
00179       transform::Rigid3d::Translation(Eigen::Vector3d(max_x, max_y, 0.)));
00180 
00181   return true;
00182 }
00183 
00184 }  // namespace mapping
00185 }  // namespace cartographer


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