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 #ifndef CARTOGRAPHER_MAPPING_2D_GRID_2D_H_ 00018 #define CARTOGRAPHER_MAPPING_2D_GRID_2D_H_ 00019 00020 #include <vector> 00021 00022 #include "cartographer/mapping/2d/map_limits.h" 00023 #include "cartographer/mapping/grid_interface.h" 00024 #include "cartographer/mapping/probability_values.h" 00025 #include "cartographer/mapping/proto/2d/grid_2d.pb.h" 00026 #include "cartographer/mapping/proto/2d/submaps_options_2d.pb.h" 00027 #include "cartographer/mapping/proto/submap_visualization.pb.h" 00028 #include "cartographer/mapping/value_conversion_tables.h" 00029 00030 namespace cartographer { 00031 namespace mapping { 00032 00033 proto::GridOptions2D CreateGridOptions2D( 00034 common::LuaParameterDictionary* const parameter_dictionary); 00035 00036 enum class GridType { PROBABILITY_GRID, TSDF }; 00037 00038 class Grid2D : public GridInterface { 00039 public: 00040 Grid2D(const MapLimits& limits, float min_correspondence_cost, 00041 float max_correspondence_cost, 00042 ValueConversionTables* conversion_tables); 00043 explicit Grid2D(const proto::Grid2D& proto, 00044 ValueConversionTables* conversion_tables); 00045 00046 // Returns the limits of this Grid2D. 00047 const MapLimits& limits() const { return limits_; } 00048 00049 // Finishes the update sequence. 00050 void FinishUpdate(); 00051 00052 // Returns the correspondence cost of the cell with 'cell_index'. 00053 float GetCorrespondenceCost(const Eigen::Array2i& cell_index) const { 00054 if (!limits().Contains(cell_index)) return max_correspondence_cost_; 00055 return (*value_to_correspondence_cost_table_) 00056 [correspondence_cost_cells()[ToFlatIndex(cell_index)]]; 00057 } 00058 00059 virtual GridType GetGridType() const = 0; 00060 00061 // Returns the minimum possible correspondence cost. 00062 float GetMinCorrespondenceCost() const { return min_correspondence_cost_; } 00063 00064 // Returns the maximum possible correspondence cost. 00065 float GetMaxCorrespondenceCost() const { return max_correspondence_cost_; } 00066 00067 // Returns true if the probability at the specified index is known. 00068 bool IsKnown(const Eigen::Array2i& cell_index) const { 00069 return limits_.Contains(cell_index) && 00070 correspondence_cost_cells_[ToFlatIndex(cell_index)] != 00071 kUnknownCorrespondenceValue; 00072 } 00073 00074 // Fills in 'offset' and 'limits' to define a subregion of that contains all 00075 // known cells. 00076 void ComputeCroppedLimits(Eigen::Array2i* const offset, 00077 CellLimits* const limits) const; 00078 00079 // Grows the map as necessary to include 'point'. This changes the meaning of 00080 // these coordinates going forward. This method must be called immediately 00081 // after 'FinishUpdate', before any calls to 'ApplyLookupTable'. 00082 virtual void GrowLimits(const Eigen::Vector2f& point); 00083 00084 virtual std::unique_ptr<Grid2D> ComputeCroppedGrid() const = 0; 00085 00086 virtual proto::Grid2D ToProto() const; 00087 00088 virtual bool DrawToSubmapTexture( 00089 proto::SubmapQuery::Response::SubmapTexture* const texture, 00090 transform::Rigid3d local_pose) const = 0; 00091 00092 protected: 00093 void GrowLimits(const Eigen::Vector2f& point, 00094 const std::vector<std::vector<uint16>*>& grids, 00095 const std::vector<uint16>& grids_unknown_cell_values); 00096 00097 const std::vector<uint16>& correspondence_cost_cells() const { 00098 return correspondence_cost_cells_; 00099 } 00100 const std::vector<int>& update_indices() const { return update_indices_; } 00101 const Eigen::AlignedBox2i& known_cells_box() const { 00102 return known_cells_box_; 00103 } 00104 00105 std::vector<uint16>* mutable_correspondence_cost_cells() { 00106 return &correspondence_cost_cells_; 00107 } 00108 00109 std::vector<int>* mutable_update_indices() { return &update_indices_; } 00110 Eigen::AlignedBox2i* mutable_known_cells_box() { return &known_cells_box_; } 00111 00112 // Converts a 'cell_index' into an index into 'cells_'. 00113 int ToFlatIndex(const Eigen::Array2i& cell_index) const { 00114 CHECK(limits_.Contains(cell_index)) << cell_index; 00115 return limits_.cell_limits().num_x_cells * cell_index.y() + cell_index.x(); 00116 } 00117 00118 private: 00119 MapLimits limits_; 00120 std::vector<uint16> correspondence_cost_cells_; 00121 float min_correspondence_cost_; 00122 float max_correspondence_cost_; 00123 std::vector<int> update_indices_; 00124 00125 // Bounding box of known cells to efficiently compute cropping limits. 00126 Eigen::AlignedBox2i known_cells_box_; 00127 const std::vector<float>* value_to_correspondence_cost_table_; 00128 }; 00129 00130 } // namespace mapping 00131 } // namespace cartographer 00132 00133 #endif // CARTOGRAPHER_MAPPING_2D_GRID_2D_H_