00001 /** 00002 \file Robots/LoBot/misc/LoLRFData.H 00003 00004 \brief A helper for the lobot::LaserRangeFinder class that copies all 00005 the current measurements and provides a convenient API to use them. 00006 00007 This file defines a class that provides a convenient API for copying 00008 and then using the current measurements from lobot::LaserRangeFinder. 00009 It was written so as to keep lobot::LaserRangeFinder unchanged and 00010 uncluttered and to provide a quick way to make local copies of the LRF 00011 measurements so that behaviours don't hold the update locks for very 00012 long. 00013 */ 00014 00015 // //////////////////////////////////////////////////////////////////// // 00016 // The iLab Neuromorphic Vision C++ Toolkit - Copyright (C) 2000-2005 // 00017 // by the University of Southern California (USC) and the iLab at USC. // 00018 // See http://iLab.usc.edu for information about this project. // 00019 // //////////////////////////////////////////////////////////////////// // 00020 // Major portions of the iLab Neuromorphic Vision Toolkit are protected // 00021 // under the U.S. patent ``Computation of Intrinsic Perceptual Saliency // 00022 // in Visual Environments, and Applications'' by Christof Koch and // 00023 // Laurent Itti, California Institute of Technology, 2001 (patent // 00024 // pending; application number 09/912,225 filed July 23, 2001; see // 00025 // http://pair.uspto.gov/cgi-bin/final/home.pl for current status). // 00026 // //////////////////////////////////////////////////////////////////// // 00027 // This file is part of the iLab Neuromorphic Vision C++ Toolkit. // 00028 // // 00029 // The iLab Neuromorphic Vision C++ Toolkit is free software; you can // 00030 // redistribute it and/or modify it under the terms of the GNU General // 00031 // Public License as published by the Free Software Foundation; either // 00032 // version 2 of the License, or (at your option) any later version. // 00033 // // 00034 // The iLab Neuromorphic Vision C++ Toolkit is distributed in the hope // 00035 // that it will be useful, but WITHOUT ANY WARRANTY; without even the // 00036 // implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR // 00037 // PURPOSE. See the GNU General Public License for more details. // 00038 // // 00039 // You should have received a copy of the GNU General Public License // 00040 // along with the iLab Neuromorphic Vision C++ Toolkit; if not, write // 00041 // to the Free Software Foundation, Inc., 59 Temple Place, Suite 330, // 00042 // Boston, MA 02111-1307 USA. // 00043 // //////////////////////////////////////////////////////////////////// // 00044 // 00045 // Primary maintainer for this file: mviswana usc edu 00046 // $HeadURL: svn://isvn.usc.edu/software/invt/trunk/saliency/src/Robots/LoBot/io/LoLRFData.H $ 00047 // $Id: LoLRFData.H 13434 2010-05-19 04:36:08Z mviswana $ 00048 // 00049 00050 #ifndef LOBOT_LRF_DATA_DOT_H 00051 #define LOBOT_LRF_DATA_DOT_H 00052 00053 //------------------------------ HEADERS -------------------------------- 00054 00055 // lobot headers 00056 #include "Robots/LoBot/io/LoLaserRangeFinder.H" 00057 #include "Robots/LoBot/util/range.hh" 00058 00059 // Standard C++ headers 00060 #include <vector> 00061 00062 //----------------------------- NAMESPACE ------------------------------- 00063 00064 namespace lobot { 00065 00066 //------------------------- CLASS DEFINITION ---------------------------- 00067 00068 /** 00069 \class lobot::LRFData 00070 \brief Convenient API to locally copy and use LRF measurements so as 00071 to minimize update lock usage by different behaviours. 00072 00073 This class provides a convenient API for behaviours to make local 00074 copies of the current LRF measurements so that they don't have to hold 00075 on to the Robolocust update lock for very long. 00076 */ 00077 class LRFData { 00078 /// What is the device's range? 00079 range<int> m_angle_range, m_distance_range ; 00080 00081 /// The current distance measurements. 00082 int* m_distances ; 00083 00084 public: 00085 /// Initialization 00086 LRFData(const LaserRangeFinder*) ; 00087 00088 /// Copy 00089 LRFData(const LRFData&) ; 00090 00091 /// Assignment 00092 LRFData& operator=(const LRFData&) ; 00093 00094 /// What is the distance measurement (in mm) along the specified 00095 /// direction (in degrees)? A negative value is returned if the angle 00096 /// is out of range. Zero degrees corresponds to the front of the 00097 /// device. Directions to the left are positive angles and those to 00098 /// the right are negative. 00099 int distance(int angle) const ; 00100 00101 /// Convenience function to return distance corresponding to some 00102 /// angle. A negative value is returned if the angle is out of range. 00103 /// Zero degrees corresponds to the front of the device. Directions to 00104 /// the left are positive angles and those to the right are negative. 00105 int operator[](int angle) const {return distance(angle) ;} 00106 00107 /// Return all the distance readings via an STL vector. 00108 std::vector<int> distances() const ; 00109 00110 /// What is the device's distance measurement range? 00111 //@{ 00112 range<int> distance_range() const {return m_distance_range ;} 00113 int min_distance() const {return m_distance_range.min() ;} 00114 int max_distance() const {return m_distance_range.max() ;} 00115 //@} 00116 00117 /// Retrieve the device's angular range. 00118 //@{ 00119 range<int> angular_range() const {return m_angle_range ;} 00120 int min_angle() const {return m_angle_range.min() ;} 00121 int max_angle() const {return m_angle_range.max() ;} 00122 //@} 00123 00124 /// Return the average distance in the given angular range. 00125 //@{ 00126 float average_distance(int min_angle, int max_angle) const ; 00127 float average_distance(const range<int>& R) const { 00128 return average_distance(R.min(), R.max()) ; 00129 } 00130 //@} 00131 00132 /// Clean-up 00133 ~LRFData() ; 00134 00135 /// This inner class encapsulates an LRF reading, viz., a distance 00136 /// measurement plus the angle at which that measurement was made. 00137 class Reading { 00138 /// This class holds a distance measurement plus its corresponding 00139 /// angle. 00140 int m_angle, m_distance ; 00141 00142 public: 00143 /// Constructor 00144 Reading(int angle, int distance) ; 00145 00146 /// Return the distance held by the reading. 00147 int distance() const {return m_distance ;} 00148 00149 /// Return the angle held by the reading. 00150 int angle() const {return m_angle ;} 00151 00152 /// Operator to compare readings based on their distances. 00153 bool operator<(const Reading& R) const { 00154 return m_distance < R.m_distance ; 00155 } 00156 } ; 00157 00158 /// This function returns the reading corresponding to the minimum 00159 /// distance in the given angular range. 00160 //@{ 00161 Reading min_distance(int min_angle, int max_angle) const ; 00162 Reading min_distance(const range<int>& R) const { 00163 return min_distance(R.min(), R.max()) ; 00164 } 00165 //@} 00166 } ; 00167 00168 //----------------------------------------------------------------------- 00169 00170 } // end of namespace encapsulating this file's definitions 00171 00172 #endif 00173 00174 /* So things look consistent in everyone's emacs... */ 00175 /* Local Variables: */ 00176 /* indent-tabs-mode: nil */ 00177 /* End: */