00001 /** 00002 \file Robots/LoBot/slam/LoOccGrid.H 00003 \brief A log-odds occupancy grid that acts as an obstacle map. 00004 00005 This file defines a class that implements an obstacle map for the 00006 Robolocust system. This map is an occupancy grid that holds 00007 probability values rather than simple 0/1 flags indicating the absence 00008 or presence of obstacles. Furthermore, the probabilities are stored in 00009 log-odds form. 00010 00011 The grid is discretized so that, for example, each cell represents 10 00012 sq.mm of "real" space. The range sensor readings are then binned when 00013 determining which cell in the map they "hit." 00014 00015 The occupancy grid's extents are defined by [L, R, B, T] values. 00016 */ 00017 00018 // //////////////////////////////////////////////////////////////////// // 00019 // The iLab Neuromorphic Vision C++ Toolkit - Copyright (C) 2000-2005 // 00020 // by the University of Southern California (USC) and the iLab at USC. // 00021 // See http://iLab.usc.edu for information about this project. // 00022 // //////////////////////////////////////////////////////////////////// // 00023 // Major portions of the iLab Neuromorphic Vision Toolkit are protected // 00024 // under the U.S. patent ``Computation of Intrinsic Perceptual Saliency // 00025 // in Visual Environments, and Applications'' by Christof Koch and // 00026 // Laurent Itti, California Institute of Technology, 2001 (patent // 00027 // pending; application number 09/912,225 filed July 23, 2001; see // 00028 // http://pair.uspto.gov/cgi-bin/final/home.pl for current status). // 00029 // //////////////////////////////////////////////////////////////////// // 00030 // This file is part of the iLab Neuromorphic Vision C++ Toolkit. // 00031 // // 00032 // The iLab Neuromorphic Vision C++ Toolkit is free software; you can // 00033 // redistribute it and/or modify it under the terms of the GNU General // 00034 // Public License as published by the Free Software Foundation; either // 00035 // version 2 of the License, or (at your option) any later version. // 00036 // // 00037 // The iLab Neuromorphic Vision C++ Toolkit is distributed in the hope // 00038 // that it will be useful, but WITHOUT ANY WARRANTY; without even the // 00039 // implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR // 00040 // PURPOSE. See the GNU General Public License for more details. // 00041 // // 00042 // You should have received a copy of the GNU General Public License // 00043 // along with the iLab Neuromorphic Vision C++ Toolkit; if not, write // 00044 // to the Free Software Foundation, Inc., 59 Temple Place, Suite 330, // 00045 // Boston, MA 02111-1307 USA. // 00046 // //////////////////////////////////////////////////////////////////// // 00047 // 00048 // Primary maintainer for this file: mviswana usc edu 00049 // $HeadURL: svn://isvn.usc.edu/software/invt/trunk/saliency/src/Robots/LoBot/slam/LoOccGrid.H $ 00050 // $Id: LoOccGrid.H 13559 2010-06-11 10:15:15Z mviswana $ 00051 // 00052 00053 #ifndef LOBOT_OCCUPANCY_GRID_DOT_H 00054 #define LOBOT_OCCUPANCY_GRID_DOT_H 00055 00056 //------------------------------ HEADERS -------------------------------- 00057 00058 // Standard C++ headers 00059 #include <string> 00060 #include <vector> 00061 00062 //----------------------------- NAMESPACE ------------------------------- 00063 00064 namespace lobot { 00065 00066 //------------------------- CLASS DEFINITION ---------------------------- 00067 00068 /** 00069 \class lobot::OccGrid 00070 \brief A log-odds occupancy grid. 00071 00072 This class implements an occupancy grid that is used to keep track of 00073 where obstacles are in the robot's environment. The occupancy grid's 00074 cells hold probability values rather than simple 0/1 flags to indicate 00075 the absence or presence of an obstacle. Furthermore, the probabilities 00076 are stored in log-odds form rather than directly as numbers in the 00077 [0,1] range. 00078 00079 The extents of the occupancy grid are specified using [L, R, B, T] 00080 values, which are read from the Robolocust config file. 00081 */ 00082 class OccGrid { 00083 /// The occupancy grid is represented as a single dimensional array 00084 /// stored in row-major order. 00085 //@{ 00086 typedef std::vector<float> Grid ; 00087 Grid m_grid ; 00088 //@} 00089 00090 public: 00091 /// When an "empty" occupancy grid object is created, all its 00092 /// probabilities are set to 50%. 00093 OccGrid() ; 00094 00095 /// An occupancy grid may be initialized from a file containing 00096 /// coordinates of obstacles. In this case of a known map, the cells 00097 /// containing obstacles will be assigned high likelihoods (nearly 00098 /// 100%) and the other cells will get low likelihoods (nearly 0%). 00099 OccGrid(const std::string& map_file) ; 00100 00101 /// Copy. 00102 OccGrid(const OccGrid&) ; 00103 00104 /// Assignment. 00105 OccGrid& operator=(const OccGrid&) ; 00106 00107 /// This method adds this map to the supplied map, retaining the 00108 /// result in this map object itself. 00109 OccGrid& operator+=(const OccGrid&) ; 00110 00111 /// This method adds this map to the supplied map and returns the 00112 /// result in a new map object. 00113 OccGrid operator+(const OccGrid&) const ; 00114 00115 /// This method multiplies the probabilities in this occupancy grid by 00116 /// the supplied weighting factor and returns the scaled result in a 00117 /// new occupancy grid object. 00118 OccGrid operator*(float weight) const ; 00119 00120 /// Accessors. 00121 //@{ 00122 Grid::const_iterator begin() const {return m_grid.begin() ;} 00123 Grid::const_iterator end() const {return m_grid.end() ;} 00124 //@} 00125 00126 /// These methods mark the specified cell in the occupancy grid as 00127 /// either occupied or vacant by incrementing or decrementing the 00128 /// log-odds value in that cell. 00129 //@{ 00130 void occupied(int x, int y) ; 00131 void vacant(int x, int y) ; 00132 private: 00133 void update(int x, int y, float prob_delta) ; 00134 public: 00135 //@} 00136 00137 /// Return the log-odds occupancy value stored at the specified cell. 00138 /// 00139 /// NOTE: The occupancy value of a cell is determined as a weighted 00140 /// sum of the value stored in the target cell itself and the values 00141 /// in the immediate neighbourhood of the target cell. The target 00142 /// cell's occupancy value gets the maximum weight while the 00143 /// neigbouring cells get lower weights. 00144 float get(int x, int y) const ; 00145 00146 /// This method checks if the specified cell of the occupancy grid is 00147 /// occupied. 00148 bool is_occupied(int x, int y) const ; 00149 00150 /// Check if cell is vacant. 00151 bool is_vacant(int x, int y) const {return ! is_occupied(x, y) ;} 00152 00153 /// Clean-up. 00154 ~OccGrid() ; 00155 } ; 00156 00157 //----------------------------------------------------------------------- 00158 00159 } // end of namespace encapsulating this file's definitions 00160 00161 #endif 00162 00163 /* So things look consistent in everyone's emacs... */ 00164 /* Local Variables: */ 00165 /* indent-tabs-mode: nil */ 00166 /* End: */