probability_grid_range_data_inserter_2d.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 
00017 #include "cartographer/mapping/2d/probability_grid_range_data_inserter_2d.h"
00018 
00019 #include <cstdlib>
00020 
00021 #include "Eigen/Core"
00022 #include "Eigen/Geometry"
00023 #include "cartographer/mapping/2d/xy_index.h"
00024 #include "cartographer/mapping/internal/2d/ray_to_pixel_mask.h"
00025 #include "cartographer/mapping/probability_values.h"
00026 #include "glog/logging.h"
00027 
00028 namespace cartographer {
00029 namespace mapping {
00030 namespace {
00031 
00032 // Factor for subpixel accuracy of start and end point for ray casts.
00033 constexpr int kSubpixelScale = 1000;
00034 
00035 void GrowAsNeeded(const sensor::RangeData& range_data,
00036                   ProbabilityGrid* const probability_grid) {
00037   Eigen::AlignedBox2f bounding_box(range_data.origin.head<2>());
00038   // Padding around bounding box to avoid numerical issues at cell boundaries.
00039   constexpr float kPadding = 1e-6f;
00040   for (const sensor::RangefinderPoint& hit : range_data.returns) {
00041     bounding_box.extend(hit.position.head<2>());
00042   }
00043   for (const sensor::RangefinderPoint& miss : range_data.misses) {
00044     bounding_box.extend(miss.position.head<2>());
00045   }
00046   probability_grid->GrowLimits(bounding_box.min() -
00047                                kPadding * Eigen::Vector2f::Ones());
00048   probability_grid->GrowLimits(bounding_box.max() +
00049                                kPadding * Eigen::Vector2f::Ones());
00050 }
00051 
00052 void CastRays(const sensor::RangeData& range_data,
00053               const std::vector<uint16>& hit_table,
00054               const std::vector<uint16>& miss_table,
00055               const bool insert_free_space, ProbabilityGrid* probability_grid) {
00056   GrowAsNeeded(range_data, probability_grid);
00057 
00058   const MapLimits& limits = probability_grid->limits();
00059   const double superscaled_resolution = limits.resolution() / kSubpixelScale;
00060   const MapLimits superscaled_limits(
00061       superscaled_resolution, limits.max(),
00062       CellLimits(limits.cell_limits().num_x_cells * kSubpixelScale,
00063                  limits.cell_limits().num_y_cells * kSubpixelScale));
00064   const Eigen::Array2i begin =
00065       superscaled_limits.GetCellIndex(range_data.origin.head<2>());
00066   // Compute and add the end points.
00067   std::vector<Eigen::Array2i> ends;
00068   ends.reserve(range_data.returns.size());
00069   for (const sensor::RangefinderPoint& hit : range_data.returns) {
00070     ends.push_back(superscaled_limits.GetCellIndex(hit.position.head<2>()));
00071     probability_grid->ApplyLookupTable(ends.back() / kSubpixelScale, hit_table);
00072   }
00073 
00074   if (!insert_free_space) {
00075     return;
00076   }
00077 
00078   // Now add the misses.
00079   for (const Eigen::Array2i& end : ends) {
00080     std::vector<Eigen::Array2i> ray =
00081         RayToPixelMask(begin, end, kSubpixelScale);
00082     for (const Eigen::Array2i& cell_index : ray) {
00083       probability_grid->ApplyLookupTable(cell_index, miss_table);
00084     }
00085   }
00086 
00087   // Finally, compute and add empty rays based on misses in the range data.
00088   for (const sensor::RangefinderPoint& missing_echo : range_data.misses) {
00089     std::vector<Eigen::Array2i> ray = RayToPixelMask(
00090         begin, superscaled_limits.GetCellIndex(missing_echo.position.head<2>()),
00091         kSubpixelScale);
00092     for (const Eigen::Array2i& cell_index : ray) {
00093       probability_grid->ApplyLookupTable(cell_index, miss_table);
00094     }
00095   }
00096 }
00097 }  // namespace
00098 
00099 proto::ProbabilityGridRangeDataInserterOptions2D
00100 CreateProbabilityGridRangeDataInserterOptions2D(
00101     common::LuaParameterDictionary* parameter_dictionary) {
00102   proto::ProbabilityGridRangeDataInserterOptions2D options;
00103   options.set_hit_probability(
00104       parameter_dictionary->GetDouble("hit_probability"));
00105   options.set_miss_probability(
00106       parameter_dictionary->GetDouble("miss_probability"));
00107   options.set_insert_free_space(
00108       parameter_dictionary->HasKey("insert_free_space")
00109           ? parameter_dictionary->GetBool("insert_free_space")
00110           : true);
00111   CHECK_GT(options.hit_probability(), 0.5);
00112   CHECK_LT(options.miss_probability(), 0.5);
00113   return options;
00114 }
00115 
00116 ProbabilityGridRangeDataInserter2D::ProbabilityGridRangeDataInserter2D(
00117     const proto::ProbabilityGridRangeDataInserterOptions2D& options)
00118     : options_(options),
00119       hit_table_(ComputeLookupTableToApplyCorrespondenceCostOdds(
00120           Odds(options.hit_probability()))),
00121       miss_table_(ComputeLookupTableToApplyCorrespondenceCostOdds(
00122           Odds(options.miss_probability()))) {}
00123 
00124 void ProbabilityGridRangeDataInserter2D::Insert(
00125     const sensor::RangeData& range_data, GridInterface* const grid) const {
00126   ProbabilityGrid* const probability_grid = static_cast<ProbabilityGrid*>(grid);
00127   CHECK(probability_grid != nullptr);
00128   // By not finishing the update after hits are inserted, we give hits priority
00129   // (i.e. no hits will be ignored because of a miss in the same cell).
00130   CastRays(range_data, hit_table_, miss_table_, options_.insert_free_space(),
00131            probability_grid);
00132   probability_grid->FinishUpdate();
00133 }
00134 
00135 }  // namespace mapping
00136 }  // namespace cartographer


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