00001 /** 00002 \file Robots/LoBot/slam/LoMap.H 00003 \brief An application-wide data structure holding the occupancy grid 00004 used mainly for visualization and state communication between 00005 different behaviours. 00006 00007 This file defines a class that implements an application-wide obstacle 00008 map for the Robolocust system. This map is an occupancy grid that 00009 holds probability values rather than simple 0/1 flags indicating the 00010 absence or presence of obstacles. The probabilities are represented as 00011 bytes ranging from 0 to 255. High values indicate free space while low 00012 values indicate obstacles. 00013 00014 In addition to the obstacle map, this data structure also holds the 00015 robot's current pose w.r.t. the map. 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/LoMap.H $ 00050 // $Id: LoMap.H 13732 2010-07-29 14:16:35Z mviswana $ 00051 // 00052 00053 #ifndef LOBOT_MAP_DOT_H 00054 #define LOBOT_MAP_DOT_H 00055 00056 //------------------------------ HEADERS -------------------------------- 00057 00058 // lobot headers 00059 #include "Robots/LoBot/slam/LoPose.H" 00060 #include "Robots/LoBot/ui/LoDrawable.H" 00061 #include "Robots/LoBot/thread/LoRWLock.H" 00062 #include "Robots/LoBot/thread/LoMutex.H" 00063 00064 // Standard C++ headers 00065 #include <vector> 00066 #include <utility> 00067 00068 //----------------------------- NAMESPACE ------------------------------- 00069 00070 namespace lobot { 00071 00072 //------------------------- CLASS DEFINITION ---------------------------- 00073 00074 // Forward declarations 00075 class OccGrid ; 00076 00077 /** 00078 \class lobot::Map 00079 \brief An application-wide obstacle map. 00080 00081 This class implements an occupancy grid that is used to keep track of 00082 where obstacles are. The occupancy grid's cells hold probability 00083 values rather than simple 0/1 flags to indicate the absence or 00084 presence of an obstacle. The probabilities are bytes in the [0,255] 00085 range rather than floats in the [0,1] range. Furthermore, high values 00086 indicate free space while low ones denote the presence of obstacles. 00087 00088 In addition to holding the occupancy map, this class also keeps track 00089 of the robot's current pose, which is specified using an (x, y, theta) 00090 triple. 00091 */ 00092 class Map : public Drawable { 00093 // Prevent copy and assignment 00094 Map(const Map&) ; 00095 Map& operator=(const Map&) ; 00096 00097 /// The occupancy grid is represented as a single dimensional array 00098 /// stored in row-major order. Each cell in the array holds a number 00099 /// in the range [0,255]. Higher values imply greater certainty that a 00100 /// cell is free; lower values indicate greater certainty that a cell 00101 /// has an obstacle in it. 00102 std::vector<unsigned char> m_grid ; 00103 00104 /// In addition to the occupancy grid, this data structure also keeps 00105 /// track of the robot's current pose w.r.t. the map. 00106 Pose m_pose ; 00107 00108 /// Many behaviours/modules may be interested in hearing about pose 00109 /// updates. Therefore, the map maintains a list of callback functions 00110 /// to inform interested parties about pose updates. 00111 /// 00112 /// NOTE: Clients should take care that the pose update hooks not 00113 /// perform lengthy operations so as to not hold up the thread that 00114 /// originated the pose update. 00115 public: 00116 //@{ 00117 typedef void (*PoseCB)(const Pose&, unsigned long client_data) ; 00118 typedef std::pair<PoseCB, unsigned long> PoseHook ; 00119 private: 00120 std::vector<PoseHook> m_pose_hooks ; 00121 //@} 00122 00123 /// Multiple behaviours can access the map at the same time. For 00124 /// example, a SLAM behaviour can be busy building the map and 00125 /// updating the pose while a goal behaviour uses the map and pose to 00126 /// guide the robot towards some specific location. Therefore, we 00127 /// should protect simultaneous accesses to the map's grid, pose and 00128 /// related data structures. 00129 /// 00130 /// NOTE: More threads read the pose than update it. Therefore, it 00131 /// makes sense to use a read/write lock for it rather than a mutex. 00132 //@{ 00133 Mutex m_grid_mutex ; 00134 RWLock m_pose_lock ; 00135 Mutex m_pose_hooks_mutex ; 00136 //@} 00137 00138 public: 00139 /// Initialization: creates an empty map. 00140 Map() ; 00141 00142 /// This method allows clients to add pose update hooks so they can be 00143 /// informed when the robot's pose gets updated. 00144 void add_pose_hook(const PoseHook&) ; 00145 00146 /// This method updates this map object using the data from the 00147 /// supplied log-odds occupancy grid. 00148 void update(const OccGrid&) ; 00149 00150 /// This method updates the pose. 00151 void update(const Pose&) ; 00152 00153 /// This method returns the robot's current pose w.r.t. to the map. 00154 Pose current_pose() const ; 00155 00156 /// This method returns a square subportion of the occupancy map 00157 /// centered at the robot's current position. The size of the submap 00158 /// will 2*w+1, where w is supplied by the client. 00159 std::vector<unsigned char> submap(int w) const ; 00160 00161 private: 00162 /// OpenGL initialization. 00163 void gl_init() ; 00164 00165 /// Map visualization. 00166 void render_me() ; 00167 00168 /// OpenGL clean-up. 00169 void gl_cleanup() ; 00170 } ; 00171 00172 //----------------------------------------------------------------------- 00173 00174 } // end of namespace encapsulating this file's definitions 00175 00176 #endif 00177 00178 /* So things look consistent in everyone's emacs... */ 00179 /* Local Variables: */ 00180 /* indent-tabs-mode: nil */ 00181 /* End: */