Karto.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2010 SRI International
00003  *
00004  * This program is free software: you can redistribute it and/or modify
00005  * it under the terms of the GNU Lesser General Public License as published by
00006  * the Free Software Foundation, either version 3 of the License, or
00007  * (at your option) any later version.
00008  *
00009  * This program is distributed in the hope that it will be useful,
00010  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00011  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00012  * GNU Lesser General Public License for more details.
00013  *
00014  * You should have received a copy of the GNU Lesser General Public License
00015  * along with this program.  If not, see <http://www.gnu.org/licenses/>.
00016  */
00017 
00018 #ifndef OPEN_KARTO_KARTO_H
00019 #define OPEN_KARTO_KARTO_H
00020 
00021 #include <string>
00022 #include <fstream>
00023 #include <limits>
00024 #include <algorithm>
00025 #include <map>
00026 #include <vector>
00027 #include <iostream>
00028 #include <iomanip>
00029 #include <sstream>
00030 #include <stdexcept>
00031 
00032 #include <math.h>
00033 #include <float.h>
00034 #include <stdio.h>
00035 #include <assert.h>
00036 #include <string.h>
00037 #include <boost/thread.hpp>
00038 
00039 #ifdef USE_POCO
00040 #include <Poco/Mutex.h>
00041 #endif
00042 
00043 #include <open_karto/Math.h>
00044 #include <open_karto/Macros.h>
00045 
00046 #define KARTO_Object(name) \
00047   virtual const char* GetClassName() const { return #name; } \
00048   virtual kt_objecttype GetObjectType() const { return ObjectType_##name; }
00049 
00050 typedef kt_int32u kt_objecttype;
00051 
00052 const kt_objecttype ObjectType_None                 = 0x00000000;
00053 const kt_objecttype ObjectType_Sensor               = 0x00001000;
00054 const kt_objecttype ObjectType_SensorData           = 0x00002000;
00055 const kt_objecttype ObjectType_CustomData           = 0x00004000;
00056 const kt_objecttype ObjectType_Misc                 = 0x10000000;
00057 
00058 const kt_objecttype ObjectType_Drive                = ObjectType_Sensor | 0x01;
00059 const kt_objecttype ObjectType_LaserRangeFinder     = ObjectType_Sensor | 0x02;
00060 const kt_objecttype ObjectType_Camera               = ObjectType_Sensor | 0x04;
00061 
00062 const kt_objecttype ObjectType_DrivePose            = ObjectType_SensorData | 0x01;
00063 const kt_objecttype ObjectType_LaserRangeScan       = ObjectType_SensorData | 0x02;
00064 const kt_objecttype ObjectType_LocalizedRangeScan   = ObjectType_SensorData | 0x04;
00065 const kt_objecttype ObjectType_CameraImage          = ObjectType_SensorData | 0x08;
00066 
00067 const kt_objecttype ObjectType_Header               = ObjectType_Misc | 0x01;
00068 const kt_objecttype ObjectType_Parameters           = ObjectType_Misc | 0x02;
00069 const kt_objecttype ObjectType_DatasetInfo          = ObjectType_Misc | 0x04;
00070 const kt_objecttype ObjectType_Module               = ObjectType_Misc | 0x08;
00071 
00072 namespace karto
00073 {
00074 
00079 
00083   class KARTO_EXPORT Exception
00084   {
00085   public:
00091     Exception(const std::string& rMessage = "Karto Exception", kt_int32s errorCode = 0)
00092       : m_Message(rMessage)
00093       , m_ErrorCode(errorCode)
00094     {
00095     }
00096 
00100     Exception(const Exception& rException)
00101       : m_Message(rException.m_Message)
00102       , m_ErrorCode(rException.m_ErrorCode)
00103     {
00104     }
00105 
00109     virtual ~Exception()
00110     {
00111     }
00112 
00113   public:
00117     Exception& operator = (const Exception& rException)
00118     {
00119       m_Message = rException.m_Message;
00120       m_ErrorCode = rException.m_ErrorCode;
00121 
00122       return *this;
00123     }
00124 
00125   public:
00130     const std::string& GetErrorMessage() const
00131     {
00132       return m_Message;
00133     }
00134 
00139     kt_int32s GetErrorCode()
00140     {
00141       return m_ErrorCode;
00142     }
00143 
00144   public:
00150     friend KARTO_EXPORT std::ostream& operator << (std::ostream& rStream, Exception& rException);
00151 
00152   private:
00153     std::string m_Message;
00154     kt_int32s m_ErrorCode;
00155   };  // class Exception
00156 
00160 
00165   class KARTO_EXPORT NonCopyable
00166   {
00167   private:
00168     NonCopyable(const NonCopyable&);
00169     const NonCopyable& operator=(const NonCopyable&);
00170 
00171   protected:
00172     NonCopyable()
00173     {
00174     }
00175 
00176     virtual ~NonCopyable()
00177     {
00178     }
00179   };  // class NonCopyable
00180 
00184 
00188   template <class T>
00189   class Singleton
00190   {
00191   public:
00195     Singleton()
00196       : m_pPointer(NULL)
00197     {
00198     }
00199 
00203     virtual ~Singleton()
00204     {
00205       delete m_pPointer;
00206     }
00207 
00212     T* Get()
00213     {
00214 #ifdef USE_POCO
00215       Poco::FastMutex::ScopedLock lock(m_Mutex);
00216 #endif
00217       if (m_pPointer == NULL)
00218       {
00219         m_pPointer = new T;
00220       }
00221 
00222       return m_pPointer;
00223     }
00224 
00225   private:
00226     T* m_pPointer;
00227 
00228 #ifdef USE_POCO
00229     Poco::FastMutex m_Mutex;
00230 #endif
00231 
00232   private:
00233     Singleton(const Singleton&);
00234     const Singleton& operator=(const Singleton&);
00235   };
00236 
00240 
00244   class KARTO_EXPORT Functor
00245   {
00246   public:
00250     virtual void operator() (kt_int32u) {};
00251   };  // Functor
00252 
00256 
00257   class AbstractParameter;
00258 
00262   typedef std::vector<AbstractParameter*> ParameterVector;
00263 
00267   class KARTO_EXPORT ParameterManager : public NonCopyable
00268   {
00269   public:
00273     ParameterManager()
00274     {
00275     }
00276 
00280     virtual ~ParameterManager()
00281     {
00282       Clear();
00283     }
00284 
00285   public:
00290     void Add(AbstractParameter* pParameter);
00291 
00297     AbstractParameter* Get(const std::string& rName)
00298     {
00299       if (m_ParameterLookup.find(rName) != m_ParameterLookup.end())
00300       {
00301         return m_ParameterLookup[rName];
00302       }
00303 
00304       std::cout << "Unknown parameter: " << rName << std::endl;
00305 
00306       return NULL;
00307     }
00308 
00312     void Clear();
00313 
00318     inline const ParameterVector& GetParameterVector() const
00319     {
00320       return m_Parameters;
00321     }
00322 
00323   public:
00329     AbstractParameter* operator() (const std::string& rName)
00330     {
00331       return Get(rName);
00332     }
00333 
00334   private:
00335     ParameterManager(const ParameterManager&);
00336     const ParameterManager& operator=(const ParameterManager&);
00337 
00338   private:
00339     ParameterVector m_Parameters;
00340     std::map<std::string, AbstractParameter*> m_ParameterLookup;
00341   };  // ParameterManager
00342 
00346 
00347   // valid names
00348   // 'Test' -- no scope
00349   // '/Test' -- no scope will be parsed to 'Test'
00350   // '/scope/Test' - 'scope' scope and 'Test' name
00351   // '/scope/name/Test' - 'scope/name' scope and 'Test' name
00352   //
00353   class Name
00354   {
00355   public:
00359     Name()
00360     {
00361     }
00362 
00366     Name(const std::string& rName)
00367     {
00368       Parse(rName);
00369     }
00370 
00374     Name(const Name& rOther)
00375       : m_Name(rOther.m_Name)
00376       , m_Scope(rOther.m_Scope)
00377     {
00378     }
00379 
00383     virtual ~Name()
00384     {
00385     }
00386 
00387   public:
00392     inline const std::string& GetName() const
00393     {
00394       return m_Name;
00395     }
00396 
00401     inline void SetName(const std::string& rName)
00402     {
00403       std::string::size_type pos = rName.find_last_of('/');
00404       if (pos != 0 && pos != std::string::npos)
00405       {
00406         throw Exception("Name can't contain a scope!");
00407       }
00408 
00409       m_Name = rName;
00410     }
00411 
00416     inline const std::string& GetScope() const
00417     {
00418       return m_Scope;
00419     }
00420 
00425     inline void SetScope(const std::string& rScope)
00426     {
00427       m_Scope = rScope;
00428     }
00429 
00434     inline std::string ToString() const
00435     {
00436       if (m_Scope == "")
00437       {
00438         return m_Name;
00439       }
00440       else
00441       {
00442         std::string name;
00443         name.append("/");
00444         name.append(m_Scope);
00445         name.append("/");
00446         name.append(m_Name);
00447 
00448         return name;
00449       }
00450     }
00451 
00452   public:
00456     Name& operator = (const Name& rOther)
00457     {
00458       if (&rOther != this)
00459       {
00460         m_Name = rOther.m_Name;
00461         m_Scope = rOther.m_Scope;
00462       }
00463 
00464       return *this;
00465     }
00466 
00470     kt_bool operator == (const Name& rOther) const
00471     {
00472       return (m_Name == rOther.m_Name) && (m_Scope == rOther.m_Scope);
00473     }
00474 
00478     kt_bool operator != (const Name& rOther) const
00479     {
00480       return !(*this == rOther);
00481     }
00482 
00486     kt_bool operator < (const Name& rOther) const
00487     {
00488       return ToString() < rOther.ToString();
00489     }
00490 
00496     friend inline std::ostream& operator << (std::ostream& rStream, const Name& rName)
00497     {
00498       rStream << rName.ToString();
00499       return rStream;
00500     }
00501 
00502   private:
00507     void Parse(const std::string& rName)
00508     {
00509       std::string::size_type pos = rName.find_last_of('/');
00510 
00511       if (pos == std::string::npos)
00512       {
00513         m_Name = rName;
00514       }
00515       else
00516       {
00517         m_Scope = rName.substr(0, pos);
00518         m_Name = rName.substr(pos+1, rName.size());
00519 
00520         // remove '/' from m_Scope if first!!
00521         if (m_Scope.size() > 0 && m_Scope[0] == '/')
00522         {
00523           m_Scope = m_Scope.substr(1, m_Scope.size());
00524         }
00525       }
00526     }
00527 
00532     void Validate(const std::string& rName)
00533     {
00534       if (rName.empty())
00535       {
00536         return;
00537       }
00538 
00539       char c = rName[0];
00540       if (IsValidFirst(c))
00541       {
00542         for (size_t i = 1; i < rName.size(); ++i)
00543         {
00544           c = rName[i];
00545           if (!IsValid(c))
00546           {
00547             throw Exception("Invalid character in name. Valid characters must be within the ranges A-Z, a-z, 0-9, '/', '_' and '-'.");
00548           }
00549         }
00550       }
00551       else
00552       {
00553         throw Exception("Invalid first character in name. Valid characters must be within the ranges A-Z, a-z, and '/'.");
00554       }
00555     }
00556 
00562     inline kt_bool IsValidFirst(char c)
00563     {
00564       return (isalpha(c) || c == '/');
00565     }
00566 
00572     inline kt_bool IsValid(char c)
00573     {
00574       return (isalnum(c) || c == '/' || c == '_' || c == '-');
00575     }
00576 
00577   private:
00578     std::string m_Name;
00579     std::string m_Scope;
00580   };
00581 
00585 
00589   class KARTO_EXPORT Object : public NonCopyable
00590   {
00591   public:
00595     Object();
00596 
00601     Object(const Name& rName);
00602 
00606     virtual ~Object();
00607 
00608   public:
00613     inline const Name& GetName() const
00614     {
00615       return m_Name;
00616     }
00617 
00622     virtual const char* GetClassName() const = 0;
00623 
00628     virtual kt_objecttype GetObjectType() const = 0;
00629 
00634     virtual inline ParameterManager* GetParameterManager()
00635     {
00636       return m_pParameterManager;
00637     }
00638 
00644     inline AbstractParameter* GetParameter(const std::string& rName) const
00645     {
00646       return m_pParameterManager->Get(rName);
00647     }
00648 
00654     template<typename T>
00655     inline void SetParameter(const std::string& rName, T value);
00656 
00661     inline const ParameterVector& GetParameters() const
00662     {
00663       return m_pParameterManager->GetParameterVector();
00664     }
00665 
00666   private:
00667     Object(const Object&);
00668     const Object& operator=(const Object&);
00669 
00670   private:
00671     Name m_Name;
00672     ParameterManager* m_pParameterManager;
00673   };
00674 
00678   typedef std::vector<Object*> ObjectVector;
00679 
00683 
00689   inline kt_bool IsSensor(Object* pObject)
00690   {
00691     return (pObject->GetObjectType() & ObjectType_Sensor) == ObjectType_Sensor;
00692   }
00693 
00699   inline kt_bool IsSensorData(Object* pObject)
00700   {
00701     return (pObject->GetObjectType() & ObjectType_SensorData) == ObjectType_SensorData;
00702   }
00703 
00709   inline kt_bool IsLaserRangeFinder(Object* pObject)
00710   {
00711     return (pObject->GetObjectType() & ObjectType_LaserRangeFinder) == ObjectType_LaserRangeFinder;
00712   }
00713 
00719   inline kt_bool IsLocalizedRangeScan(Object* pObject)
00720   {
00721     return (pObject->GetObjectType() & ObjectType_LocalizedRangeScan) == ObjectType_LocalizedRangeScan;
00722   }
00723 
00729   inline kt_bool IsParameters(Object* pObject)
00730   {
00731     return (pObject->GetObjectType() & ObjectType_Parameters) == ObjectType_Parameters;
00732   }
00733 
00739   inline kt_bool IsDatasetInfo(Object* pObject)
00740   {
00741     return (pObject->GetObjectType() & ObjectType_DatasetInfo) == ObjectType_DatasetInfo;
00742   }
00743 
00747 
00751   class KARTO_EXPORT Module : public Object
00752   {
00753   public:
00754     // @cond EXCLUDE
00755     KARTO_Object(Module)
00756     // @endcond
00757 
00758   public:
00763     Module(const std::string& rName);
00764 
00768     virtual ~Module();
00769 
00770   public:
00774     virtual void Reset() = 0;
00775 
00779     virtual kt_bool Process(karto::Object*)
00780     {
00781       return false;
00782     }
00783 
00784   private:
00785     Module(const Module&);
00786     const Module& operator=(const Module&);
00787   };
00788 
00792 
00796   template<typename T>
00797   class Size2
00798   {
00799   public:
00803     Size2()
00804       : m_Width(0)
00805       , m_Height(0)
00806     {
00807     }
00808 
00814     Size2(T width, T height)
00815       : m_Width(width)
00816       , m_Height(height)
00817     {
00818     }
00819 
00824     Size2(const Size2& rOther)
00825       : m_Width(rOther.m_Width)
00826       , m_Height(rOther.m_Height)
00827     {
00828     }
00829 
00830   public:
00835     inline const T GetWidth() const
00836     {
00837       return m_Width;
00838     }
00839 
00844     inline void SetWidth(T width)
00845     {
00846       m_Width = width;
00847     }
00848 
00853     inline const T GetHeight() const
00854     {
00855       return m_Height;
00856     }
00857 
00862     inline void SetHeight(T height)
00863     {
00864       m_Height = height;
00865     }
00866 
00870     inline Size2& operator = (const Size2& rOther)
00871     {
00872       m_Width = rOther.m_Width;
00873       m_Height = rOther.m_Height;
00874 
00875       return(*this);
00876     }
00877 
00881     inline kt_bool operator == (const Size2& rOther) const
00882     {
00883       return (m_Width == rOther.m_Width && m_Height == rOther.m_Height);
00884     }
00885 
00889     inline kt_bool operator != (const Size2& rOther) const
00890     {
00891       return (m_Width != rOther.m_Width || m_Height != rOther.m_Height);
00892     }
00893 
00899     friend inline std::ostream& operator << (std::ostream& rStream, const Size2& rSize)
00900     {
00901       rStream << "(" << rSize.m_Width << ", " << rSize.m_Height << ")";
00902       return rStream;
00903     }
00904 
00905   private:
00906     T m_Width;
00907     T m_Height;
00908   };  // Size2<T>
00909 
00913 
00917   template<typename T>
00918   class Vector2
00919   {
00920   public:
00924     Vector2()
00925     {
00926       m_Values[0] = 0;
00927       m_Values[1] = 0;
00928     }
00929 
00935     Vector2(T x, T y)
00936     {
00937       m_Values[0] = x;
00938       m_Values[1] = y;
00939     }
00940 
00941   public:
00946     inline const T& GetX() const
00947     {
00948       return m_Values[0];
00949     }
00950 
00955     inline void SetX(const T& x)
00956     {
00957       m_Values[0] = x;
00958     }
00959 
00964     inline const T& GetY() const
00965     {
00966       return m_Values[1];
00967     }
00968 
00973     inline void SetY(const T& y)
00974     {
00975       m_Values[1] = y;
00976     }
00977 
00982     inline void MakeFloor(const Vector2& rOther)
00983     {
00984       if ( rOther.m_Values[0] < m_Values[0] ) m_Values[0] = rOther.m_Values[0];
00985       if ( rOther.m_Values[1] < m_Values[1] ) m_Values[1] = rOther.m_Values[1];
00986     }
00987 
00992     inline void MakeCeil(const Vector2& rOther)
00993     {
00994       if ( rOther.m_Values[0] > m_Values[0] ) m_Values[0] = rOther.m_Values[0];
00995       if ( rOther.m_Values[1] > m_Values[1] ) m_Values[1] = rOther.m_Values[1];
00996     }
00997 
01002     inline kt_double SquaredLength() const
01003     {
01004       return math::Square(m_Values[0]) + math::Square(m_Values[1]);
01005     }
01006 
01011     inline kt_double Length() const
01012     {
01013       return sqrt(SquaredLength());
01014     }
01015 
01020     inline kt_double SquaredDistance(const Vector2& rOther) const
01021     {
01022       return (*this - rOther).SquaredLength();
01023     }
01024 
01030     inline kt_double Distance(const Vector2& rOther) const
01031     {
01032       return sqrt(SquaredDistance(rOther));
01033     }
01034 
01035   public:
01039     inline void operator += (const Vector2& rOther)
01040     {
01041       m_Values[0] += rOther.m_Values[0];
01042       m_Values[1] += rOther.m_Values[1];
01043     }
01044 
01048     inline void operator -= (const Vector2& rOther)
01049     {
01050       m_Values[0] -= rOther.m_Values[0];
01051       m_Values[1] -= rOther.m_Values[1];
01052     }
01053 
01059     inline const Vector2 operator + (const Vector2& rOther) const
01060     {
01061       return Vector2(m_Values[0] + rOther.m_Values[0], m_Values[1] + rOther.m_Values[1]);
01062     }
01063 
01069     inline const Vector2 operator - (const Vector2& rOther) const
01070     {
01071       return Vector2(m_Values[0] - rOther.m_Values[0], m_Values[1] - rOther.m_Values[1]);
01072     }
01073 
01078     inline void operator /= (T scalar)
01079     {
01080       m_Values[0] /= scalar;
01081       m_Values[1] /= scalar;
01082     }
01083 
01089     inline const Vector2 operator / (T scalar) const
01090     {
01091       return Vector2(m_Values[0] / scalar, m_Values[1] / scalar);
01092     }
01093 
01099     inline kt_double operator * (const Vector2& rOther) const
01100     {
01101       return m_Values[0] * rOther.m_Values[0] + m_Values[1] * rOther.m_Values[1];
01102     }
01103 
01108     inline const Vector2 operator * (T scalar) const
01109     {
01110       return Vector2(m_Values[0] * scalar, m_Values[1] * scalar);
01111     }
01112 
01117     inline const Vector2 operator - (T scalar) const
01118     {
01119       return Vector2(m_Values[0] - scalar, m_Values[1] - scalar);
01120     }
01121 
01126     inline void operator *= (T scalar)
01127     {
01128       m_Values[0] *= scalar;
01129       m_Values[1] *= scalar;
01130     }
01131 
01136     inline kt_bool operator == (const Vector2& rOther) const
01137     {
01138       return (m_Values[0] == rOther.m_Values[0] && m_Values[1] == rOther.m_Values[1]);
01139     }
01140 
01145     inline kt_bool operator != (const Vector2& rOther) const
01146     {
01147       return (m_Values[0] != rOther.m_Values[0] || m_Values[1] != rOther.m_Values[1]);
01148     }
01149 
01155     inline kt_bool operator < (const Vector2& rOther) const
01156     {
01157       if (m_Values[0] < rOther.m_Values[0])
01158         return true;
01159       else if (m_Values[0] > rOther.m_Values[0])
01160         return false;
01161       else
01162         return (m_Values[1] < rOther.m_Values[1]);
01163     }
01164 
01170     friend inline std::ostream& operator << (std::ostream& rStream, const Vector2& rVector)
01171     {
01172       rStream << rVector.GetX() << " " << rVector.GetY();
01173       return rStream;
01174     }
01175 
01180     friend inline std::istream& operator >> (std::istream& rStream, const Vector2& /*rVector*/)
01181     {
01182       // Implement me!!  TODO(lucbettaieb): What the what?  Do I need to implement this?
01183       return rStream;
01184     }
01185 
01186   private:
01187     T m_Values[2];
01188   };  // Vector2<T>
01189 
01193   typedef std::vector< Vector2<kt_double> > PointVectorDouble;
01194 
01198 
01202   template<typename T>
01203   class Vector3
01204   {
01205   public:
01209     Vector3()
01210     {
01211       m_Values[0] = 0;
01212       m_Values[1] = 0;
01213       m_Values[2] = 0;
01214     }
01215 
01222     Vector3(T x, T y, T z)
01223     {
01224       m_Values[0] = x;
01225       m_Values[1] = y;
01226       m_Values[2] = z;
01227     }
01228 
01233     Vector3(const Vector3& rOther)
01234     {
01235       m_Values[0] = rOther.m_Values[0];
01236       m_Values[1] = rOther.m_Values[1];
01237       m_Values[2] = rOther.m_Values[2];
01238     }
01239 
01240   public:
01245     inline const T& GetX() const
01246     {
01247       return m_Values[0];
01248     }
01249 
01254     inline void SetX(const T& x)
01255     {
01256       m_Values[0] = x;
01257     }
01258 
01263     inline const T& GetY() const
01264     {
01265       return m_Values[1];
01266     }
01267 
01272     inline void SetY(const T& y)
01273     {
01274       m_Values[1] = y;
01275     }
01276 
01281     inline const T& GetZ() const
01282     {
01283       return m_Values[2];
01284     }
01285 
01290     inline void SetZ(const T& z)
01291     {
01292       m_Values[2] = z;
01293     }
01294 
01299     inline void MakeFloor(const Vector3& rOther)
01300     {
01301       if (rOther.m_Values[0] < m_Values[0]) m_Values[0] = rOther.m_Values[0];
01302       if (rOther.m_Values[1] < m_Values[1]) m_Values[1] = rOther.m_Values[1];
01303       if (rOther.m_Values[2] < m_Values[2]) m_Values[2] = rOther.m_Values[2];
01304     }
01305 
01310     inline void MakeCeil(const Vector3& rOther)
01311     {
01312       if (rOther.m_Values[0] > m_Values[0]) m_Values[0] = rOther.m_Values[0];
01313       if (rOther.m_Values[1] > m_Values[1]) m_Values[1] = rOther.m_Values[1];
01314       if (rOther.m_Values[2] > m_Values[2]) m_Values[2] = rOther.m_Values[2];
01315     }
01316 
01321     inline kt_double SquaredLength() const
01322     {
01323       return math::Square(m_Values[0]) + math::Square(m_Values[1]) + math::Square(m_Values[2]);
01324     }
01325 
01330     inline kt_double Length() const
01331     {
01332       return sqrt(SquaredLength());
01333     }
01334 
01339     inline std::string ToString() const
01340     {
01341       std::stringstream converter;
01342       converter.precision(std::numeric_limits<double>::digits10);
01343 
01344       converter << GetX() << " " << GetY() << " " << GetZ();
01345 
01346       return converter.str();
01347     }
01348 
01349   public:
01353     inline Vector3& operator = (const Vector3& rOther)
01354     {
01355       m_Values[0] = rOther.m_Values[0];
01356       m_Values[1] = rOther.m_Values[1];
01357       m_Values[2] = rOther.m_Values[2];
01358 
01359       return *this;
01360     }
01361 
01367     inline const Vector3 operator + (const Vector3& rOther) const
01368     {
01369       return Vector3(m_Values[0] + rOther.m_Values[0],
01370                      m_Values[1] + rOther.m_Values[1],
01371                      m_Values[2] + rOther.m_Values[2]);
01372     }
01373 
01379     inline const Vector3 operator + (kt_double scalar) const
01380     {
01381       return Vector3(m_Values[0] + scalar,
01382                      m_Values[1] + scalar,
01383                      m_Values[2] + scalar);
01384     }
01385 
01391     inline const Vector3 operator - (const Vector3& rOther) const
01392     {
01393       return Vector3(m_Values[0] - rOther.m_Values[0],
01394                      m_Values[1] - rOther.m_Values[1],
01395                      m_Values[2] - rOther.m_Values[2]);
01396     }
01397 
01403     inline const Vector3 operator - (kt_double scalar) const
01404     {
01405       return Vector3(m_Values[0] - scalar, m_Values[1] - scalar, m_Values[2] - scalar);
01406     }
01407 
01412     inline const Vector3 operator * (T scalar) const
01413     {
01414       return Vector3(m_Values[0] * scalar, m_Values[1] * scalar, m_Values[2] * scalar);
01415     }
01416 
01421     inline kt_bool operator == (const Vector3& rOther) const
01422     {
01423       return (m_Values[0] == rOther.m_Values[0] &&
01424               m_Values[1] == rOther.m_Values[1] &&
01425               m_Values[2] == rOther.m_Values[2]);
01426     }
01427 
01432     inline kt_bool operator != (const Vector3& rOther) const
01433     {
01434       return (m_Values[0] != rOther.m_Values[0] ||
01435               m_Values[1] != rOther.m_Values[1] ||
01436               m_Values[2] != rOther.m_Values[2]);
01437     }
01438 
01444     friend inline std::ostream& operator << (std::ostream& rStream, const Vector3& rVector)
01445     {
01446       rStream << rVector.ToString();
01447       return rStream;
01448     }
01449 
01454     friend inline std::istream& operator >> (std::istream& rStream, const Vector3& /*rVector*/)
01455     {
01456       // Implement me!!
01457       return rStream;
01458     }
01459 
01460   private:
01461     T m_Values[3];
01462   };  // Vector3
01463 
01467 
01489   class Quaternion
01490   {
01491   public:
01495     inline Quaternion()
01496     {
01497       m_Values[0] = 0.0;
01498       m_Values[1] = 0.0;
01499       m_Values[2] = 0.0;
01500       m_Values[3] = 1.0;
01501     }
01502 
01510     inline Quaternion(kt_double x, kt_double y, kt_double z, kt_double w)
01511     {
01512       m_Values[0] = x;
01513       m_Values[1] = y;
01514       m_Values[2] = z;
01515       m_Values[3] = w;
01516     }
01517 
01521     inline Quaternion(const Quaternion& rQuaternion)
01522     {
01523       m_Values[0] = rQuaternion.m_Values[0];
01524       m_Values[1] = rQuaternion.m_Values[1];
01525       m_Values[2] = rQuaternion.m_Values[2];
01526       m_Values[3] = rQuaternion.m_Values[3];
01527     }
01528 
01529   public:
01534     inline kt_double GetX() const
01535     {
01536       return m_Values[0];
01537     }
01538 
01543     inline void SetX(kt_double x)
01544     {
01545       m_Values[0] = x;
01546     }
01547 
01552     inline kt_double GetY() const
01553     {
01554       return m_Values[1];
01555     }
01556 
01561     inline void SetY(kt_double y)
01562     {
01563       m_Values[1] = y;
01564     }
01565 
01570     inline kt_double GetZ() const
01571     {
01572       return m_Values[2];
01573     }
01574 
01579     inline void SetZ(kt_double z)
01580     {
01581       m_Values[2] = z;
01582     }
01583 
01588     inline kt_double GetW() const
01589     {
01590       return m_Values[3];
01591     }
01592 
01597     inline void SetW(kt_double w)
01598     {
01599       m_Values[3] = w;
01600     }
01601 
01609     void ToEulerAngles(kt_double& rYaw, kt_double& rPitch, kt_double& rRoll) const
01610     {
01611       kt_double test = m_Values[0] * m_Values[1] + m_Values[2] * m_Values[3];
01612 
01613       if (test > 0.499)
01614       {
01615         // singularity at north pole
01616         rYaw = 2 * atan2(m_Values[0], m_Values[3]);;
01617         rPitch = KT_PI_2;
01618         rRoll = 0;
01619       }
01620       else if (test < -0.499)
01621       {
01622         // singularity at south pole
01623         rYaw = -2 * atan2(m_Values[0], m_Values[3]);
01624         rPitch = -KT_PI_2;
01625         rRoll = 0;
01626       }
01627       else
01628       {
01629         kt_double sqx = m_Values[0] * m_Values[0];
01630         kt_double sqy = m_Values[1] * m_Values[1];
01631         kt_double sqz = m_Values[2] * m_Values[2];
01632 
01633         rYaw = atan2(2 * m_Values[1] * m_Values[3] - 2 * m_Values[0] * m_Values[2], 1 - 2 * sqy - 2 * sqz);
01634         rPitch = asin(2 * test);
01635         rRoll = atan2(2 * m_Values[0] * m_Values[3] - 2 * m_Values[1] * m_Values[2], 1 - 2 * sqx - 2 * sqz);
01636       }
01637     }
01638 
01646     void FromEulerAngles(kt_double yaw, kt_double pitch, kt_double roll)
01647     {
01648       kt_double angle;
01649 
01650       angle = yaw * 0.5;
01651       kt_double cYaw = cos(angle);
01652       kt_double sYaw = sin(angle);
01653 
01654       angle = pitch * 0.5;
01655       kt_double cPitch = cos(angle);
01656       kt_double sPitch = sin(angle);
01657 
01658       angle = roll * 0.5;
01659       kt_double cRoll = cos(angle);
01660       kt_double sRoll = sin(angle);
01661 
01662       m_Values[0] = sYaw * sPitch * cRoll + cYaw * cPitch * sRoll;
01663       m_Values[1] = sYaw * cPitch * cRoll + cYaw * sPitch * sRoll;
01664       m_Values[2] = cYaw * sPitch * cRoll - sYaw * cPitch * sRoll;
01665       m_Values[3] = cYaw * cPitch * cRoll - sYaw * sPitch * sRoll;
01666     }
01667 
01672     inline Quaternion& operator = (const Quaternion& rQuaternion)
01673     {
01674       m_Values[0] = rQuaternion.m_Values[0];
01675       m_Values[1] = rQuaternion.m_Values[1];
01676       m_Values[2] = rQuaternion.m_Values[2];
01677       m_Values[3] = rQuaternion.m_Values[3];
01678 
01679       return(*this);
01680     }
01681 
01686     inline kt_bool operator == (const Quaternion& rOther) const
01687     {
01688       return (m_Values[0] == rOther.m_Values[0] &&
01689               m_Values[1] == rOther.m_Values[1] &&
01690               m_Values[2] == rOther.m_Values[2] &&
01691               m_Values[3] == rOther.m_Values[3]);
01692     }
01693 
01698     inline kt_bool operator != (const Quaternion& rOther) const
01699     {
01700       return (m_Values[0] != rOther.m_Values[0] ||
01701               m_Values[1] != rOther.m_Values[1] ||
01702               m_Values[2] != rOther.m_Values[2] ||
01703               m_Values[3] != rOther.m_Values[3]);
01704     }
01705 
01711     friend inline std::ostream& operator << (std::ostream& rStream, const Quaternion& rQuaternion)
01712     {
01713       rStream << rQuaternion.m_Values[0] << " "
01714               << rQuaternion.m_Values[1] << " "
01715               << rQuaternion.m_Values[2] << " "
01716               << rQuaternion.m_Values[3];
01717       return rStream;
01718     }
01719 
01720   private:
01721     kt_double m_Values[4];
01722   };
01723 
01727 
01732   template<typename T>
01733   class Rectangle2
01734   {
01735   public:
01739     Rectangle2()
01740     {
01741     }
01742 
01750     Rectangle2(T x, T y, T width, T height)
01751       : m_Position(x, y)
01752       , m_Size(width, height)
01753     {
01754     }
01755 
01761     Rectangle2(const Vector2<T>& rPosition, const Size2<T>& rSize)
01762       : m_Position(rPosition)
01763       , m_Size(rSize)
01764     {
01765     }
01766 
01770     Rectangle2(const Rectangle2& rOther)
01771       : m_Position(rOther.m_Position)
01772       , m_Size(rOther.m_Size)
01773     {
01774     }
01775 
01776   public:
01781     inline T GetX() const
01782     {
01783       return m_Position.GetX();
01784     }
01785 
01790     inline void SetX(T x)
01791     {
01792       m_Position.SetX(x);
01793     }
01794 
01799     inline T GetY() const
01800     {
01801       return m_Position.GetY();
01802     }
01803 
01808     inline void SetY(T y)
01809     {
01810       m_Position.SetY(y);
01811     }
01812 
01817     inline T GetWidth() const
01818     {
01819       return m_Size.GetWidth();
01820     }
01821 
01826     inline void SetWidth(T width)
01827     {
01828       m_Size.SetWidth(width);
01829     }
01830 
01835     inline T GetHeight() const
01836     {
01837       return m_Size.GetHeight();
01838     }
01839 
01844     inline void SetHeight(T height)
01845     {
01846       m_Size.SetHeight(height);
01847     }
01848 
01853     inline const Vector2<T>& GetPosition() const
01854     {
01855       return m_Position;
01856     }
01857 
01863     inline void SetPosition(const T& rX, const T& rY)
01864     {
01865       m_Position = Vector2<T>(rX, rY);
01866     }
01867 
01872     inline void SetPosition(const Vector2<T>& rPosition)
01873     {
01874       m_Position = rPosition;
01875     }
01876 
01881     inline const Size2<T>& GetSize() const
01882     {
01883       return m_Size;
01884     }
01885 
01890     inline void SetSize(const Size2<T>& rSize)
01891     {
01892       m_Size = rSize;
01893     }
01894 
01899     inline const Vector2<T> GetCenter() const
01900     {
01901       return Vector2<T>(m_Position.GetX() + m_Size.GetWidth() * 0.5, m_Position.GetY() + m_Size.GetHeight() * 0.5);
01902     }
01903 
01904   public:
01908     Rectangle2& operator = (const Rectangle2& rOther)
01909     {
01910       m_Position = rOther.m_Position;
01911       m_Size = rOther.m_Size;
01912 
01913       return *this;
01914     }
01915 
01919     inline kt_bool operator == (const Rectangle2& rOther) const
01920     {
01921       return (m_Position == rOther.m_Position && m_Size == rOther.m_Size);
01922     }
01923 
01927     inline kt_bool operator != (const Rectangle2& rOther) const
01928     {
01929       return (m_Position != rOther.m_Position || m_Size != rOther.m_Size);
01930     }
01931 
01932   private:
01933     Vector2<T> m_Position;
01934     Size2<T> m_Size;
01935   };  // Rectangle2
01936 
01940 
01941   class Pose3;
01942 
01946   class Pose2
01947   {
01948   public:
01952     Pose2()
01953       : m_Heading(0.0)
01954     {
01955     }
01956 
01962     Pose2(const Vector2<kt_double>& rPosition, kt_double heading)
01963       : m_Position(rPosition)
01964       , m_Heading(heading)
01965     {
01966     }
01967 
01974     Pose2(kt_double x, kt_double y, kt_double heading)
01975       : m_Position(x, y)
01976       , m_Heading(heading)
01977     {
01978     }
01979 
01983     Pose2(const Pose3& rPose);
01984 
01988     Pose2(const Pose2& rOther)
01989       : m_Position(rOther.m_Position)
01990       , m_Heading(rOther.m_Heading)
01991     {
01992     }
01993 
01994   public:
01999     inline kt_double GetX() const
02000     {
02001       return m_Position.GetX();
02002     }
02003 
02008     inline void SetX(kt_double x)
02009     {
02010       m_Position.SetX(x);
02011     }
02012 
02017     inline kt_double GetY() const
02018     {
02019       return m_Position.GetY();
02020     }
02021 
02026     inline void SetY(kt_double y)
02027     {
02028       m_Position.SetY(y);
02029     }
02030 
02035     inline const Vector2<kt_double>& GetPosition() const
02036     {
02037       return m_Position;
02038     }
02039 
02044     inline void SetPosition(const Vector2<kt_double>& rPosition)
02045     {
02046       m_Position = rPosition;
02047     }
02048 
02053     inline kt_double GetHeading() const
02054     {
02055       return m_Heading;
02056     }
02057 
02062     inline void SetHeading(kt_double heading)
02063     {
02064       m_Heading = heading;
02065     }
02066 
02071     inline kt_double SquaredDistance(const Pose2& rOther) const
02072     {
02073       return m_Position.SquaredDistance(rOther.m_Position);
02074     }
02075 
02076   public:
02080     inline Pose2& operator = (const Pose2& rOther)
02081     {
02082       m_Position = rOther.m_Position;
02083       m_Heading = rOther.m_Heading;
02084 
02085       return *this;
02086     }
02087 
02091     inline kt_bool operator == (const Pose2& rOther) const
02092     {
02093       return (m_Position == rOther.m_Position && m_Heading == rOther.m_Heading);
02094     }
02095 
02099     inline kt_bool operator != (const Pose2& rOther) const
02100     {
02101       return (m_Position != rOther.m_Position || m_Heading != rOther.m_Heading);
02102     }
02103 
02107     inline void operator += (const Pose2& rOther)
02108     {
02109       m_Position += rOther.m_Position;
02110       m_Heading = math::NormalizeAngle(m_Heading + rOther.m_Heading);
02111     }
02112 
02118     inline Pose2 operator + (const Pose2& rOther) const
02119     {
02120       return Pose2(m_Position + rOther.m_Position, math::NormalizeAngle(m_Heading + rOther.m_Heading));
02121     }
02122 
02128     inline Pose2 operator - (const Pose2& rOther) const
02129     {
02130       return Pose2(m_Position - rOther.m_Position, math::NormalizeAngle(m_Heading - rOther.m_Heading));
02131     }
02132 
02137     friend inline std::istream& operator >> (std::istream& rStream, const Pose2& /*rPose*/)
02138     {
02139       // Implement me!!
02140       return rStream;
02141     }
02142 
02148     friend inline std::ostream& operator << (std::ostream& rStream, const Pose2& rPose)
02149     {
02150       rStream << rPose.m_Position.GetX() << " " << rPose.m_Position.GetY() << " " << rPose.m_Heading;
02151       return rStream;
02152     }
02153 
02154   private:
02155     Vector2<kt_double> m_Position;
02156 
02157     kt_double m_Heading;
02158   };  // Pose2
02159 
02163   typedef std::vector< Pose2 > Pose2Vector;
02164 
02168 
02176   class Pose3
02177   {
02178   public:
02182     Pose3()
02183     {
02184     }
02185 
02190     Pose3(const Vector3<kt_double>& rPosition)
02191       : m_Position(rPosition)
02192     {
02193     }
02194 
02200     Pose3(const Vector3<kt_double>& rPosition, const karto::Quaternion& rOrientation)
02201       : m_Position(rPosition)
02202       , m_Orientation(rOrientation)
02203     {
02204     }
02205 
02209     Pose3(const Pose3& rOther)
02210       : m_Position(rOther.m_Position)
02211       , m_Orientation(rOther.m_Orientation)
02212     {
02213     }
02214 
02218     Pose3(const Pose2& rPose)
02219     {
02220       m_Position = Vector3<kt_double>(rPose.GetX(), rPose.GetY(), 0.0);
02221       m_Orientation.FromEulerAngles(rPose.GetHeading(), 0.0, 0.0);
02222     }
02223 
02224   public:
02229     inline const Vector3<kt_double>& GetPosition() const
02230     {
02231       return m_Position;
02232     }
02233 
02238     inline void SetPosition(const Vector3<kt_double>& rPosition)
02239     {
02240       m_Position = rPosition;
02241     }
02242 
02247     inline const Quaternion& GetOrientation() const
02248     {
02249       return m_Orientation;
02250     }
02251 
02256     inline void SetOrientation(const Quaternion& rOrientation)
02257     {
02258       m_Orientation = rOrientation;
02259     }
02260 
02265     inline std::string ToString()
02266     {
02267       std::stringstream converter;
02268       converter.precision(std::numeric_limits<double>::digits10);
02269 
02270       converter << GetPosition() << " " << GetOrientation();
02271 
02272       return converter.str();
02273     }
02274 
02275   public:
02279     inline Pose3& operator = (const Pose3& rOther)
02280     {
02281       m_Position = rOther.m_Position;
02282       m_Orientation = rOther.m_Orientation;
02283 
02284       return *this;
02285     }
02286 
02290     inline kt_bool operator == (const Pose3& rOther) const
02291     {
02292       return (m_Position == rOther.m_Position && m_Orientation == rOther.m_Orientation);
02293     }
02294 
02298     inline kt_bool operator != (const Pose3& rOther) const
02299     {
02300       return (m_Position != rOther.m_Position || m_Orientation != rOther.m_Orientation);
02301     }
02302 
02308     friend inline std::ostream& operator << (std::ostream& rStream, const Pose3& rPose)
02309     {
02310       rStream << rPose.GetPosition() << ", " << rPose.GetOrientation();
02311       return rStream;
02312     }
02313 
02318     friend inline std::istream& operator >> (std::istream& rStream, const Pose3& /*rPose*/)
02319     {
02320       // Implement me!!
02321       return rStream;
02322     }
02323 
02324   private:
02325     Vector3<kt_double> m_Position;
02326     Quaternion m_Orientation;
02327   };  // Pose3
02328 
02332 
02336   class Matrix3
02337   {
02338   public:
02342     Matrix3()
02343     {
02344       Clear();
02345     }
02346 
02350     inline Matrix3(const Matrix3& rOther)
02351     {
02352       memcpy(m_Matrix, rOther.m_Matrix, 9*sizeof(kt_double));
02353     }
02354 
02355   public:
02359     void SetToIdentity()
02360     {
02361       memset(m_Matrix, 0, 9*sizeof(kt_double));
02362 
02363       for (kt_int32s i = 0; i < 3; i++)
02364       {
02365         m_Matrix[i][i] = 1.0;
02366       }
02367     }
02368 
02372     void Clear()
02373     {
02374       memset(m_Matrix, 0, 9*sizeof(kt_double));
02375     }
02376 
02384     void FromAxisAngle(kt_double x, kt_double y, kt_double z, const kt_double radians)
02385     {
02386       kt_double cosRadians = cos(radians);
02387       kt_double sinRadians = sin(radians);
02388       kt_double oneMinusCos = 1.0 - cosRadians;
02389 
02390       kt_double xx = x * x;
02391       kt_double yy = y * y;
02392       kt_double zz = z * z;
02393 
02394       kt_double xyMCos = x * y * oneMinusCos;
02395       kt_double xzMCos = x * z * oneMinusCos;
02396       kt_double yzMCos = y * z * oneMinusCos;
02397 
02398       kt_double xSin = x * sinRadians;
02399       kt_double ySin = y * sinRadians;
02400       kt_double zSin = z * sinRadians;
02401 
02402       m_Matrix[0][0] = xx * oneMinusCos + cosRadians;
02403       m_Matrix[0][1] = xyMCos - zSin;
02404       m_Matrix[0][2] = xzMCos + ySin;
02405 
02406       m_Matrix[1][0] = xyMCos + zSin;
02407       m_Matrix[1][1] = yy * oneMinusCos + cosRadians;
02408       m_Matrix[1][2] = yzMCos - xSin;
02409 
02410       m_Matrix[2][0] = xzMCos - ySin;
02411       m_Matrix[2][1] = yzMCos + xSin;
02412       m_Matrix[2][2] = zz * oneMinusCos + cosRadians;
02413     }
02414 
02419     Matrix3 Transpose() const
02420     {
02421       Matrix3 transpose;
02422 
02423       for (kt_int32u row = 0; row < 3; row++)
02424       {
02425         for (kt_int32u col = 0; col < 3; col++)
02426         {
02427           transpose.m_Matrix[row][col] = m_Matrix[col][row];
02428         }
02429       }
02430 
02431       return transpose;
02432     }
02433 
02437     Matrix3 Inverse() const
02438     {
02439       Matrix3 kInverse = *this;
02440       kt_bool haveInverse = InverseFast(kInverse, 1e-14);
02441       if (haveInverse == false)
02442       {
02443         assert(false);
02444       }
02445       return kInverse;
02446     }
02447 
02452     kt_bool InverseFast(Matrix3& rkInverse, kt_double fTolerance = KT_TOLERANCE) const
02453     {
02454       // Invert a 3x3 using cofactors.  This is about 8 times faster than
02455       // the Numerical Recipes code which uses Gaussian elimination.
02456       rkInverse.m_Matrix[0][0] = m_Matrix[1][1]*m_Matrix[2][2] - m_Matrix[1][2]*m_Matrix[2][1];
02457       rkInverse.m_Matrix[0][1] = m_Matrix[0][2]*m_Matrix[2][1] - m_Matrix[0][1]*m_Matrix[2][2];
02458       rkInverse.m_Matrix[0][2] = m_Matrix[0][1]*m_Matrix[1][2] - m_Matrix[0][2]*m_Matrix[1][1];
02459       rkInverse.m_Matrix[1][0] = m_Matrix[1][2]*m_Matrix[2][0] - m_Matrix[1][0]*m_Matrix[2][2];
02460       rkInverse.m_Matrix[1][1] = m_Matrix[0][0]*m_Matrix[2][2] - m_Matrix[0][2]*m_Matrix[2][0];
02461       rkInverse.m_Matrix[1][2] = m_Matrix[0][2]*m_Matrix[1][0] - m_Matrix[0][0]*m_Matrix[1][2];
02462       rkInverse.m_Matrix[2][0] = m_Matrix[1][0]*m_Matrix[2][1] - m_Matrix[1][1]*m_Matrix[2][0];
02463       rkInverse.m_Matrix[2][1] = m_Matrix[0][1]*m_Matrix[2][0] - m_Matrix[0][0]*m_Matrix[2][1];
02464       rkInverse.m_Matrix[2][2] = m_Matrix[0][0]*m_Matrix[1][1] - m_Matrix[0][1]*m_Matrix[1][0];
02465 
02466       kt_double fDet = m_Matrix[0][0]*rkInverse.m_Matrix[0][0] +
02467                        m_Matrix[0][1]*rkInverse.m_Matrix[1][0] +
02468                        m_Matrix[0][2]*rkInverse.m_Matrix[2][0];
02469 
02470       if (fabs(fDet) <= fTolerance)
02471       {
02472         return false;
02473       }
02474 
02475       kt_double fInvDet = 1.0/fDet;
02476       for (size_t row = 0; row < 3; row++)
02477       {
02478         for (size_t col = 0; col < 3; col++)
02479         {
02480           rkInverse.m_Matrix[row][col] *= fInvDet;
02481         }
02482       }
02483 
02484       return true;
02485     }
02486 
02491     inline std::string ToString() const
02492     {
02493       std::stringstream converter;
02494       converter.precision(std::numeric_limits<double>::digits10);
02495 
02496       for (int row = 0; row < 3; row++)
02497       {
02498         for (int col = 0; col < 3; col++)
02499         {
02500           converter << m_Matrix[row][col] << " ";
02501         }
02502       }
02503 
02504       return converter.str();
02505     }
02506 
02507   public:
02511     inline Matrix3& operator = (const Matrix3& rOther)
02512     {
02513       memcpy(m_Matrix, rOther.m_Matrix, 9*sizeof(kt_double));
02514       return *this;
02515     }
02516 
02523     inline kt_double& operator()(kt_int32u row, kt_int32u column)
02524     {
02525       return m_Matrix[row][column];
02526     }
02527 
02534     inline kt_double operator()(kt_int32u row, kt_int32u column) const
02535     {
02536       return m_Matrix[row][column];
02537     }
02538 
02544     Matrix3 operator * (const Matrix3& rOther) const
02545     {
02546       Matrix3 product;
02547 
02548       for (size_t row = 0; row < 3; row++)
02549       {
02550         for (size_t col = 0; col < 3; col++)
02551         {
02552           product.m_Matrix[row][col] = m_Matrix[row][0]*rOther.m_Matrix[0][col] +
02553                                        m_Matrix[row][1]*rOther.m_Matrix[1][col] +
02554                                        m_Matrix[row][2]*rOther.m_Matrix[2][col];
02555         }
02556       }
02557 
02558       return product;
02559     }
02560 
02566     inline Pose2 operator * (const Pose2& rPose2) const
02567     {
02568       Pose2 pose2;
02569 
02570       pose2.SetX(m_Matrix[0][0] * rPose2.GetX() + m_Matrix[0][1] *
02571                  rPose2.GetY() + m_Matrix[0][2] * rPose2.GetHeading());
02572       pose2.SetY(m_Matrix[1][0] * rPose2.GetX() + m_Matrix[1][1] *
02573                  rPose2.GetY() + m_Matrix[1][2] * rPose2.GetHeading());
02574       pose2.SetHeading(m_Matrix[2][0] * rPose2.GetX() + m_Matrix[2][1] *
02575                        rPose2.GetY() + m_Matrix[2][2] * rPose2.GetHeading());
02576 
02577       return pose2;
02578     }
02579 
02584     inline void operator += (const Matrix3& rkMatrix)
02585     {
02586       for (kt_int32u row = 0; row < 3; row++)
02587       {
02588         for (kt_int32u col = 0; col < 3; col++)
02589         {
02590           m_Matrix[row][col] += rkMatrix.m_Matrix[row][col];
02591         }
02592       }
02593     }
02594 
02600     friend inline std::ostream& operator << (std::ostream& rStream, const Matrix3& rMatrix)
02601     {
02602       rStream << rMatrix.ToString();
02603       return rStream;
02604     }
02605 
02606   private:
02607     kt_double m_Matrix[3][3];
02608   };  // Matrix3
02609 
02613 
02617   class Matrix
02618   {
02619   public:
02623     Matrix(kt_int32u rows, kt_int32u columns)
02624       : m_Rows(rows)
02625       , m_Columns(columns)
02626       , m_pData(NULL)
02627     {
02628       Allocate();
02629 
02630       Clear();
02631     }
02632 
02636     virtual ~Matrix()
02637     {
02638       delete [] m_pData;
02639     }
02640 
02641   public:
02645     void Clear()
02646     {
02647       if (m_pData != NULL)
02648       {
02649         memset(m_pData, 0, sizeof(kt_double) * m_Rows * m_Columns);
02650       }
02651     }
02652 
02657     inline kt_int32u GetRows() const
02658     {
02659       return m_Rows;
02660     }
02661 
02666     inline kt_int32u GetColumns() const
02667     {
02668       return m_Columns;
02669     }
02670 
02677     inline kt_double& operator()(kt_int32u row, kt_int32u column)
02678     {
02679       RangeCheck(row, column);
02680 
02681       return m_pData[row + column * m_Rows];
02682     }
02683 
02690     inline const kt_double& operator()(kt_int32u row, kt_int32u column) const
02691     {
02692       RangeCheck(row, column);
02693 
02694       return m_pData[row + column * m_Rows];
02695     }
02696 
02697   private:
02701     void Allocate()
02702     {
02703       try
02704       {
02705         if (m_pData != NULL)
02706         {
02707           delete[] m_pData;
02708         }
02709 
02710         m_pData = new kt_double[m_Rows * m_Columns];
02711       }
02712       catch (const std::bad_alloc& ex)
02713       {
02714         throw Exception("Matrix allocation error");
02715       }
02716 
02717       if (m_pData == NULL)
02718       {
02719         throw Exception("Matrix allocation error");
02720       }
02721     }
02722 
02728     inline void RangeCheck(kt_int32u row, kt_int32u column) const
02729     {
02730       if (math::IsUpTo(row, m_Rows) == false)
02731       {
02732         throw Exception("Matrix - RangeCheck ERROR!!!!");
02733       }
02734 
02735       if (math::IsUpTo(column, m_Columns) == false)
02736       {
02737         throw Exception("Matrix - RangeCheck ERROR!!!!");
02738       }
02739     }
02740 
02741   private:
02742     kt_int32u m_Rows;
02743     kt_int32u m_Columns;
02744 
02745     kt_double* m_pData;
02746   };  // Matrix
02747 
02751 
02755   class BoundingBox2
02756   {
02757   public:
02758     /*
02759      * Default constructor
02760      */
02761     BoundingBox2()
02762       : m_Minimum(999999999999999999.99999, 999999999999999999.99999)
02763       , m_Maximum(-999999999999999999.99999, -999999999999999999.99999)
02764     {
02765     }
02766 
02767   public:
02771     inline const Vector2<kt_double>& GetMinimum() const
02772     {
02773       return m_Minimum;
02774     }
02775 
02779     inline void SetMinimum(const Vector2<kt_double>& mMinimum)
02780     {
02781       m_Minimum = mMinimum;
02782     }
02783 
02787     inline const Vector2<kt_double>& GetMaximum() const
02788     {
02789       return m_Maximum;
02790     }
02791 
02795     inline void SetMaximum(const Vector2<kt_double>& rMaximum)
02796     {
02797       m_Maximum = rMaximum;
02798     }
02799 
02803     inline Size2<kt_double> GetSize() const
02804     {
02805       Vector2<kt_double> size = m_Maximum - m_Minimum;
02806 
02807       return Size2<kt_double>(size.GetX(), size.GetY());
02808     }
02809 
02813     inline void Add(const Vector2<kt_double>& rPoint)
02814     {
02815       m_Minimum.MakeFloor(rPoint);
02816       m_Maximum.MakeCeil(rPoint);
02817     }
02818 
02822     inline void Add(const BoundingBox2& rBoundingBox)
02823     {
02824       Add(rBoundingBox.GetMinimum());
02825       Add(rBoundingBox.GetMaximum());
02826     }
02827 
02833     inline kt_bool IsInBounds(const Vector2<kt_double>& rPoint) const
02834     {
02835       return (math::InRange(rPoint.GetX(), m_Minimum.GetX(), m_Maximum.GetX()) &&
02836               math::InRange(rPoint.GetY(), m_Minimum.GetY(), m_Maximum.GetY()));
02837     }
02838 
02839   private:
02840     Vector2<kt_double> m_Minimum;
02841     Vector2<kt_double> m_Maximum;
02842   };  // BoundingBox2
02843 
02847 
02851   class Transform
02852   {
02853   public:
02858     Transform(const Pose2& rPose)
02859     {
02860       SetTransform(Pose2(), rPose);
02861     }
02862 
02868     Transform(const Pose2& rPose1, const Pose2& rPose2)
02869     {
02870       SetTransform(rPose1, rPose2);
02871     }
02872 
02873   public:
02879     inline Pose2 TransformPose(const Pose2& rSourcePose)
02880     {
02881       Pose2 newPosition = m_Transform + m_Rotation * rSourcePose;
02882       kt_double angle = math::NormalizeAngle(rSourcePose.GetHeading() + m_Transform.GetHeading());
02883 
02884       return Pose2(newPosition.GetPosition(), angle);
02885     }
02886 
02892     inline Pose2 InverseTransformPose(const Pose2& rSourcePose)
02893     {
02894       Pose2 newPosition = m_InverseRotation * (rSourcePose - m_Transform);
02895       kt_double angle = math::NormalizeAngle(rSourcePose.GetHeading() - m_Transform.GetHeading());
02896 
02897       // components of transform
02898       return Pose2(newPosition.GetPosition(), angle);
02899     }
02900 
02901   private:
02907     void SetTransform(const Pose2& rPose1, const Pose2& rPose2)
02908     {
02909       if (rPose1 == rPose2)
02910       {
02911         m_Rotation.SetToIdentity();
02912         m_InverseRotation.SetToIdentity();
02913         m_Transform = Pose2();
02914         return;
02915       }
02916 
02917       // heading transformation
02918       m_Rotation.FromAxisAngle(0, 0, 1, rPose2.GetHeading() - rPose1.GetHeading());
02919       m_InverseRotation.FromAxisAngle(0, 0, 1, rPose1.GetHeading() - rPose2.GetHeading());
02920 
02921       // position transformation
02922       Pose2 newPosition;
02923       if (rPose1.GetX() != 0.0 || rPose1.GetY() != 0.0)
02924       {
02925         newPosition = rPose2 - m_Rotation * rPose1;
02926       }
02927       else
02928       {
02929         newPosition = rPose2;
02930       }
02931 
02932       m_Transform = Pose2(newPosition.GetPosition(), rPose2.GetHeading() - rPose1.GetHeading());
02933     }
02934 
02935   private:
02936     // pose transformation
02937     Pose2 m_Transform;
02938 
02939     Matrix3 m_Rotation;
02940     Matrix3 m_InverseRotation;
02941   };  // Transform
02942 
02946 
02950   typedef enum
02951   {
02952     LaserRangeFinder_Custom = 0,
02953 
02954     LaserRangeFinder_Sick_LMS100 = 1,
02955     LaserRangeFinder_Sick_LMS200 = 2,
02956     LaserRangeFinder_Sick_LMS291 = 3,
02957 
02958     LaserRangeFinder_Hokuyo_UTM_30LX = 4,
02959     LaserRangeFinder_Hokuyo_URG_04LX = 5
02960   } LaserRangeFinderType;
02961 
02965 
02969   class AbstractParameter
02970   {
02971   public:
02977     AbstractParameter(const std::string& rName, ParameterManager* pParameterManger = NULL)
02978       : m_Name(rName)
02979     {
02980       // if parameter manager is provided add myself to it!
02981       if (pParameterManger != NULL)
02982       {
02983         pParameterManger->Add(this);
02984       }
02985     }
02986 
02993     AbstractParameter(const std::string& rName,
02994                       const std::string& rDescription,
02995                       ParameterManager* pParameterManger = NULL)
02996       : m_Name(rName)
02997       , m_Description(rDescription)
02998     {
02999       // if parameter manager is provided add myself to it!
03000       if (pParameterManger != NULL)
03001       {
03002         pParameterManger->Add(this);
03003       }
03004     }
03005 
03009     virtual ~AbstractParameter()
03010     {
03011     }
03012 
03013   public:
03018     inline const std::string& GetName() const
03019     {
03020       return m_Name;
03021     }
03022 
03027     inline const std::string& GetDescription() const
03028     {
03029       return m_Description;
03030     }
03031 
03036     virtual const std::string GetValueAsString() const = 0;
03037 
03042     virtual void SetValueFromString(const std::string& rStringValue) = 0;
03043 
03048     virtual AbstractParameter* Clone() = 0;
03049 
03050   public:
03056     friend std::ostream& operator << (std::ostream& rStream, const AbstractParameter& rParameter)
03057     {
03058       rStream.precision(6);
03059       rStream.flags(std::ios::fixed);
03060 
03061       rStream << rParameter.GetName() << " = " << rParameter.GetValueAsString();
03062       return rStream;
03063     }
03064 
03065   private:
03066     std::string m_Name;
03067     std::string m_Description;
03068   };  // AbstractParameter
03069 
03073 
03077   template<typename T>
03078   class Parameter : public AbstractParameter
03079   {
03080   public:
03087     Parameter(const std::string& rName, T value, ParameterManager* pParameterManger = NULL)
03088       : AbstractParameter(rName, pParameterManger)
03089       , m_Value(value)
03090     {
03091     }
03092 
03100     Parameter(const std::string& rName,
03101               const std::string& rDescription,
03102               T value,
03103               ParameterManager* pParameterManger = NULL)
03104       : AbstractParameter(rName, rDescription, pParameterManger)
03105       , m_Value(value)
03106     {
03107     }
03108 
03112     virtual ~Parameter()
03113     {
03114     }
03115 
03116   public:
03121     inline const T& GetValue() const
03122     {
03123       return m_Value;
03124     }
03125 
03130     inline void SetValue(const T& rValue)
03131     {
03132       m_Value = rValue;
03133     }
03134 
03139     virtual const std::string GetValueAsString() const
03140     {
03141       std::stringstream converter;
03142       converter << m_Value;
03143       return converter.str();
03144     }
03145 
03150     virtual void SetValueFromString(const std::string& rStringValue)
03151     {
03152       std::stringstream converter;
03153       converter.str(rStringValue);
03154       converter >> m_Value;
03155     }
03156 
03161     virtual Parameter* Clone()
03162     {
03163       return new Parameter(GetName(), GetDescription(), GetValue());
03164     }
03165 
03166   public:
03170     Parameter& operator = (const Parameter& rOther)
03171     {
03172       m_Value = rOther.m_Value;
03173 
03174       return *this;
03175     }
03176 
03180     T operator = (T value)
03181     {
03182       m_Value = value;
03183 
03184       return m_Value;
03185     }
03186 
03187   protected:
03191     T m_Value;
03192   };  // Parameter
03193 
03194   template<>
03195   inline void Parameter<kt_double>::SetValueFromString(const std::string& rStringValue)
03196   {
03197     int precision = std::numeric_limits<double>::digits10;
03198     std::stringstream converter;
03199     converter.precision(precision);
03200 
03201     converter.str(rStringValue);
03202 
03203     m_Value = 0.0;
03204     converter >> m_Value;
03205   }
03206 
03207   template<>
03208   inline const std::string Parameter<kt_double>::GetValueAsString() const
03209   {
03210     std::stringstream converter;
03211     converter.precision(std::numeric_limits<double>::digits10);
03212     converter << m_Value;
03213     return converter.str();
03214   }
03215 
03216   template<>
03217   inline void Parameter<kt_bool>::SetValueFromString(const std::string& rStringValue)
03218   {
03219     if (rStringValue == "true" || rStringValue == "TRUE")
03220     {
03221       m_Value = true;
03222     }
03223     else
03224     {
03225       m_Value = false;
03226     }
03227   }
03228 
03229   template<>
03230   inline const std::string Parameter<kt_bool>::GetValueAsString() const
03231   {
03232     if (m_Value == true)
03233     {
03234       return "true";
03235     }
03236 
03237     return "false";
03238   }
03239 
03243 
03247   class ParameterEnum : public Parameter<kt_int32s>
03248   {
03249     typedef std::map<std::string, kt_int32s> EnumMap;
03250 
03251   public:
03258     ParameterEnum(const std::string& rName, kt_int32s value, ParameterManager* pParameterManger = NULL)
03259       : Parameter<kt_int32s>(rName, value, pParameterManger)
03260     {
03261     }
03262 
03266     virtual ~ParameterEnum()
03267     {
03268     }
03269 
03270   public:
03275     virtual Parameter<kt_int32s>* Clone()
03276     {
03277       ParameterEnum* pEnum = new ParameterEnum(GetName(), GetValue());
03278 
03279       pEnum->m_EnumDefines = m_EnumDefines;
03280 
03281       return pEnum;
03282     }
03283 
03288     virtual void SetValueFromString(const std::string& rStringValue)
03289     {
03290       if (m_EnumDefines.find(rStringValue) != m_EnumDefines.end())
03291       {
03292         m_Value = m_EnumDefines[rStringValue];
03293       }
03294       else
03295       {
03296         std::string validValues;
03297 
03298         const_forEach(EnumMap, &m_EnumDefines)
03299         {
03300           validValues += iter->first + ", ";
03301         }
03302 
03303         throw Exception("Unable to set enum: " + rStringValue + ". Valid values are: " + validValues);
03304       }
03305     }
03306 
03311     virtual const std::string GetValueAsString() const
03312     {
03313       const_forEach(EnumMap, &m_EnumDefines)
03314       {
03315         if (iter->second == m_Value)
03316         {
03317           return iter->first;
03318         }
03319       }
03320 
03321       throw Exception("Unable to lookup enum");
03322     }
03323 
03329     void DefineEnumValue(kt_int32s value, const std::string& rName)
03330     {
03331       if (m_EnumDefines.find(rName) == m_EnumDefines.end())
03332       {
03333         m_EnumDefines[rName] = value;
03334       }
03335       else
03336       {
03337         std::cerr << "Overriding enum value: " << m_EnumDefines[rName] << " with " << value << std::endl;
03338 
03339         m_EnumDefines[rName] = value;
03340 
03341         assert(false);
03342       }
03343     }
03344 
03345   public:
03349     ParameterEnum& operator = (const ParameterEnum& rOther)
03350     {
03351       SetValue(rOther.GetValue());
03352 
03353       return *this;
03354     }
03355 
03359     kt_int32s operator = (kt_int32s value)
03360     {
03361       SetValue(value);
03362 
03363       return m_Value;
03364     }
03365 
03366   private:
03367     EnumMap m_EnumDefines;
03368   };  // ParameterEnum
03369 
03373 
03377   class Parameters : public Object
03378   {
03379   public:
03380     // @cond EXCLUDE
03381     KARTO_Object(Parameters)
03382     // @endcond
03383 
03384   public:
03389     Parameters(const std::string& rName)
03390       : Object(rName)
03391     {
03392     }
03393 
03397     virtual ~Parameters()
03398     {
03399     }
03400 
03401   private:
03402     Parameters(const Parameters&);
03403     const Parameters& operator=(const Parameters&);
03404   };  // Parameters
03405 
03409 
03410   class SensorData;
03411 
03415   class KARTO_EXPORT Sensor : public Object
03416   {
03417   public:
03418     // @cond EXCLUDE
03419     KARTO_Object(Sensor)
03420     // @endcond
03421 
03422   protected:
03427     Sensor(const Name& rName);
03428 
03429   public:
03433     virtual ~Sensor();
03434 
03435   public:
03440     inline const Pose2& GetOffsetPose() const
03441     {
03442       return m_pOffsetPose->GetValue();
03443     }
03444 
03449     inline void SetOffsetPose(const Pose2& rPose)
03450     {
03451       m_pOffsetPose->SetValue(rPose);
03452     }
03453 
03458     virtual kt_bool Validate() = 0;
03459 
03465     virtual kt_bool Validate(SensorData* pSensorData) = 0;
03466 
03467   private:
03471     Sensor(const Sensor&);
03472 
03476     const Sensor& operator=(const Sensor&);
03477 
03478   private:
03482     Parameter<Pose2>* m_pOffsetPose;
03483   };  // Sensor
03484 
03488   typedef std::vector<Sensor*> SensorVector;
03489 
03493 
03497   typedef std::map<Name, Sensor*> SensorManagerMap;
03498 
03502   class KARTO_EXPORT SensorManager
03503   {
03504   public:
03508     SensorManager()
03509     {
03510     }
03511 
03515     virtual ~SensorManager()
03516     {
03517     }
03518 
03519   public:
03523     static SensorManager* GetInstance();
03524 
03525   public:
03533     void RegisterSensor(Sensor* pSensor, kt_bool override = false)
03534     {
03535       Validate(pSensor);
03536 
03537       if ((m_Sensors.find(pSensor->GetName()) != m_Sensors.end()) && !override)
03538       {
03539         throw Exception("Cannot register sensor: already registered: [" +
03540                         pSensor->GetName().ToString() +
03541                         "] (Consider setting 'override' to true)");
03542       }
03543 
03544       std::cout << "Registering sensor: [" << pSensor->GetName().ToString() << "]" << std::endl;
03545 
03546       m_Sensors[pSensor->GetName()] = pSensor;
03547     }
03548 
03553     void UnregisterSensor(Sensor* pSensor)
03554     {
03555       Validate(pSensor);
03556 
03557       if (m_Sensors.find(pSensor->GetName()) != m_Sensors.end())
03558       {
03559         std::cout << "Unregistering sensor: " << pSensor->GetName().ToString() << std::endl;
03560 
03561         m_Sensors.erase(pSensor->GetName());
03562       }
03563       else
03564       {
03565         throw Exception("Cannot unregister sensor: not registered: [" + pSensor->GetName().ToString() + "]");
03566       }
03567     }
03568 
03574     Sensor* GetSensorByName(const Name& rName)
03575     {
03576       if (m_Sensors.find(rName) != m_Sensors.end())
03577       {
03578         return m_Sensors[rName];
03579       }
03580 
03581       throw Exception("Sensor not registered: [" + rName.ToString() + "] (Did you add the sensor to the Dataset?)");
03582     }
03583 
03589     template<class T>
03590     T* GetSensorByName(const Name& rName)
03591     {
03592       Sensor* pSensor = GetSensorByName(rName);
03593 
03594       return dynamic_cast<T*>(pSensor);
03595     }
03596 
03601     SensorVector GetAllSensors()
03602     {
03603       SensorVector sensors;
03604 
03605       forEach(SensorManagerMap, &m_Sensors)
03606       {
03607         sensors.push_back(iter->second);
03608       }
03609 
03610       return sensors;
03611     }
03612 
03613   protected:
03618     static void Validate(Sensor* pSensor)
03619     {
03620       if (pSensor == NULL)
03621       {
03622         throw Exception("Invalid sensor:  NULL");
03623       }
03624       else if (pSensor->GetName().ToString() == "")
03625       {
03626         throw Exception("Invalid sensor:  nameless");
03627       }
03628     }
03629 
03630   protected:
03634     SensorManagerMap m_Sensors;
03635   };
03636 
03640 
03647   class Drive : public Sensor
03648   {
03649   public:
03650     // @cond EXCLUDE
03651     KARTO_Object(Drive)
03652     // @endcond
03653 
03654   public:
03658     Drive(const std::string& rName)
03659       : Sensor(rName)
03660     {
03661     }
03662 
03666     virtual ~Drive()
03667     {
03668     }
03669 
03670   public:
03671     virtual kt_bool Validate()
03672     {
03673       return true;
03674     }
03675 
03676     virtual kt_bool Validate(SensorData* pSensorData)
03677     {
03678       if (pSensorData == NULL)
03679       {
03680         return false;
03681       }
03682 
03683       return true;
03684     }
03685 
03686   private:
03687     Drive(const Drive&);
03688     const Drive& operator=(const Drive&);
03689   };  // class Drive
03690 
03694 
03695   class LocalizedRangeScan;
03696   class CoordinateConverter;
03697 
03710   class KARTO_EXPORT LaserRangeFinder : public Sensor
03711   {
03712   public:
03713     // @cond EXCLUDE
03714     KARTO_Object(LaserRangeFinder)
03715     // @endcond
03716 
03717   public:
03721     virtual ~LaserRangeFinder()
03722     {
03723     }
03724 
03725   public:
03730     inline kt_double GetMinimumRange() const
03731     {
03732       return m_pMinimumRange->GetValue();
03733     }
03734 
03739     inline void SetMinimumRange(kt_double minimumRange)
03740     {
03741       m_pMinimumRange->SetValue(minimumRange);
03742 
03743       SetRangeThreshold(GetRangeThreshold());
03744     }
03745 
03750     inline kt_double GetMaximumRange() const
03751     {
03752       return m_pMaximumRange->GetValue();
03753     }
03754 
03759     inline void SetMaximumRange(kt_double maximumRange)
03760     {
03761       m_pMaximumRange->SetValue(maximumRange);
03762 
03763       SetRangeThreshold(GetRangeThreshold());
03764     }
03765 
03770     inline kt_double GetRangeThreshold() const
03771     {
03772       return m_pRangeThreshold->GetValue();
03773     }
03774 
03779     inline void SetRangeThreshold(kt_double rangeThreshold)
03780     {
03781       // make sure rangeThreshold is within laser range finder range
03782       m_pRangeThreshold->SetValue(math::Clip(rangeThreshold, GetMinimumRange(), GetMaximumRange()));
03783 
03784       if (math::DoubleEqual(GetRangeThreshold(), rangeThreshold) == false)
03785       {
03786         std::cout << "Info: clipped range threshold to be within minimum and maximum range!" << std::endl;
03787       }
03788     }
03789 
03794     inline kt_double GetMinimumAngle() const
03795     {
03796       return m_pMinimumAngle->GetValue();
03797     }
03798 
03803     inline void SetMinimumAngle(kt_double minimumAngle)
03804     {
03805       m_pMinimumAngle->SetValue(minimumAngle);
03806 
03807       Update();
03808     }
03809 
03814     inline kt_double GetMaximumAngle() const
03815     {
03816       return m_pMaximumAngle->GetValue();
03817     }
03818 
03823     inline void SetMaximumAngle(kt_double maximumAngle)
03824     {
03825       m_pMaximumAngle->SetValue(maximumAngle);
03826 
03827       Update();
03828     }
03829 
03834     inline kt_double GetAngularResolution() const
03835     {
03836       return m_pAngularResolution->GetValue();
03837     }
03838 
03843     inline void SetAngularResolution(kt_double angularResolution)
03844     {
03845       if (m_pType->GetValue() == LaserRangeFinder_Custom)
03846       {
03847         m_pAngularResolution->SetValue(angularResolution);
03848       }
03849       else if (m_pType->GetValue() == LaserRangeFinder_Sick_LMS100)
03850       {
03851         if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.25)))
03852         {
03853           m_pAngularResolution->SetValue(math::DegreesToRadians(0.25));
03854         }
03855         else if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.50)))
03856         {
03857           m_pAngularResolution->SetValue(math::DegreesToRadians(0.50));
03858         }
03859         else
03860         {
03861           std::stringstream stream;
03862           stream << "Invalid resolution for Sick LMS100:  ";
03863           stream << angularResolution;
03864           throw Exception(stream.str());
03865         }
03866       }
03867       else if (m_pType->GetValue() == LaserRangeFinder_Sick_LMS200 ||
03868                m_pType->GetValue() == LaserRangeFinder_Sick_LMS291)
03869       {
03870         if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.25)))
03871         {
03872           m_pAngularResolution->SetValue(math::DegreesToRadians(0.25));
03873         }
03874         else if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.50)))
03875         {
03876           m_pAngularResolution->SetValue(math::DegreesToRadians(0.50));
03877         }
03878         else if (math::DoubleEqual(angularResolution, math::DegreesToRadians(1.00)))
03879         {
03880           m_pAngularResolution->SetValue(math::DegreesToRadians(1.00));
03881         }
03882         else
03883         {
03884           std::stringstream stream;
03885           stream << "Invalid resolution for Sick LMS291:  ";
03886           stream << angularResolution;
03887           throw Exception(stream.str());
03888         }
03889       }
03890       else
03891       {
03892         throw Exception("Can't set angular resolution, please create a LaserRangeFinder of type Custom");
03893       }
03894 
03895       Update();
03896     }
03897 
03901     inline kt_int32s GetType()
03902     {
03903       return m_pType->GetValue();
03904     }
03905 
03910     inline kt_int32u GetNumberOfRangeReadings() const
03911     {
03912       return m_NumberOfRangeReadings;
03913     }
03914 
03915     virtual kt_bool Validate()
03916     {
03917       Update();
03918 
03919       if (math::InRange(GetRangeThreshold(), GetMinimumRange(), GetMaximumRange()) == false)
03920       {
03921         std::cout << "Please set range threshold to a value between ["
03922                   << GetMinimumRange() << ";" << GetMaximumRange() << "]" << std::endl;
03923         return false;
03924       }
03925 
03926       return true;
03927     }
03928 
03929     virtual kt_bool Validate(SensorData* pSensorData);
03930 
03938     const PointVectorDouble GetPointReadings(LocalizedRangeScan* pLocalizedRangeScan,
03939                                             CoordinateConverter* pCoordinateConverter,
03940                                             kt_bool ignoreThresholdPoints = true,
03941                                             kt_bool flipY = false) const;
03942 
03943   public:
03950     static LaserRangeFinder* CreateLaserRangeFinder(LaserRangeFinderType type, const Name& rName)
03951     {
03952       LaserRangeFinder* pLrf = NULL;
03953 
03954       switch (type)
03955       {
03956         // see http://www.hizook.com/files/publications/SICK_LMS100.pdf
03957         // set range threshold to 18m
03958         case LaserRangeFinder_Sick_LMS100:
03959         {
03960           pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Sick LMS 100"));
03961 
03962           // Sensing range is 18 meters (at 10% reflectivity, max range of 20 meters), with an error of about 20mm
03963           pLrf->m_pMinimumRange->SetValue(0.0);
03964           pLrf->m_pMaximumRange->SetValue(20.0);
03965 
03966           // 270 degree range, 50 Hz
03967           pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-135));
03968           pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(135));
03969 
03970           // 0.25 degree angular resolution
03971           pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.25));
03972 
03973           pLrf->m_NumberOfRangeReadings = 1081;
03974         }
03975         break;
03976 
03977         // see http://www.hizook.com/files/publications/SICK_LMS200-291_Tech_Info.pdf
03978         // set range threshold to 10m
03979         case LaserRangeFinder_Sick_LMS200:
03980         {
03981           pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Sick LMS 200"));
03982 
03983           // Sensing range is 80 meters
03984           pLrf->m_pMinimumRange->SetValue(0.0);
03985           pLrf->m_pMaximumRange->SetValue(80.0);
03986 
03987           // 180 degree range, 75 Hz
03988           pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-90));
03989           pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(90));
03990 
03991           // 0.5 degree angular resolution
03992           pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.5));
03993 
03994           pLrf->m_NumberOfRangeReadings = 361;
03995         }
03996         break;
03997 
03998         // see http://www.hizook.com/files/publications/SICK_LMS200-291_Tech_Info.pdf
03999         // set range threshold to 30m
04000         case LaserRangeFinder_Sick_LMS291:
04001         {
04002           pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Sick LMS 291"));
04003 
04004           // Sensing range is 80 meters
04005           pLrf->m_pMinimumRange->SetValue(0.0);
04006           pLrf->m_pMaximumRange->SetValue(80.0);
04007 
04008           // 180 degree range, 75 Hz
04009           pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-90));
04010           pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(90));
04011 
04012           // 0.5 degree angular resolution
04013           pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.5));
04014 
04015           pLrf->m_NumberOfRangeReadings = 361;
04016         }
04017         break;
04018 
04019         // see http://www.hizook.com/files/publications/Hokuyo_UTM_LaserRangeFinder_LIDAR.pdf
04020         // set range threshold to 30m
04021         case LaserRangeFinder_Hokuyo_UTM_30LX:
04022         {
04023           pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Hokuyo UTM-30LX"));
04024 
04025           // Sensing range is 30 meters
04026           pLrf->m_pMinimumRange->SetValue(0.1);
04027           pLrf->m_pMaximumRange->SetValue(30.0);
04028 
04029           // 270 degree range, 40 Hz
04030           pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-135));
04031           pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(135));
04032 
04033           // 0.25 degree angular resolution
04034           pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.25));
04035 
04036           pLrf->m_NumberOfRangeReadings = 1081;
04037         }
04038         break;
04039 
04040         // see http://www.hizook.com/files/publications/HokuyoURG_Datasheet.pdf
04041         // set range threshold to 3.5m
04042         case LaserRangeFinder_Hokuyo_URG_04LX:
04043         {
04044           pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Hokuyo URG-04LX"));
04045 
04046           // Sensing range is 4 meters. It has detection problems when
04047           // scanning absorptive surfaces (such as black trimming).
04048           pLrf->m_pMinimumRange->SetValue(0.02);
04049           pLrf->m_pMaximumRange->SetValue(4.0);
04050 
04051           // 240 degree range, 10 Hz
04052           pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-120));
04053           pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(120));
04054 
04055           // 0.352 degree angular resolution
04056           pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.352));
04057 
04058           pLrf->m_NumberOfRangeReadings = 751;
04059         }
04060         break;
04061 
04062         case LaserRangeFinder_Custom:
04063         {
04064           pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("User-Defined LaserRangeFinder"));
04065 
04066           // Sensing range is 80 meters.
04067           pLrf->m_pMinimumRange->SetValue(0.0);
04068           pLrf->m_pMaximumRange->SetValue(80.0);
04069 
04070           // 180 degree range
04071           pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-90));
04072           pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(90));
04073 
04074           // 1.0 degree angular resolution
04075           pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(1.0));
04076 
04077           pLrf->m_NumberOfRangeReadings = 181;
04078         }
04079         break;
04080       }
04081 
04082       if (pLrf != NULL)
04083       {
04084         pLrf->m_pType->SetValue(type);
04085 
04086         Pose2 defaultOffset;
04087         pLrf->SetOffsetPose(defaultOffset);
04088       }
04089 
04090       return pLrf;
04091     }
04092 
04093   private:
04097     LaserRangeFinder(const Name& rName)
04098       : Sensor(rName)
04099       , m_NumberOfRangeReadings(0)
04100     {
04101       m_pMinimumRange = new Parameter<kt_double>("MinimumRange", 0.0, GetParameterManager());
04102       m_pMaximumRange = new Parameter<kt_double>("MaximumRange", 80.0, GetParameterManager());
04103 
04104       m_pMinimumAngle = new Parameter<kt_double>("MinimumAngle", -KT_PI_2, GetParameterManager());
04105       m_pMaximumAngle = new Parameter<kt_double>("MaximumAngle", KT_PI_2, GetParameterManager());
04106 
04107       m_pAngularResolution = new Parameter<kt_double>("AngularResolution",
04108                                                       math::DegreesToRadians(1),
04109                                                       GetParameterManager());
04110 
04111       m_pRangeThreshold = new Parameter<kt_double>("RangeThreshold", 12.0, GetParameterManager());
04112 
04113       m_pType = new ParameterEnum("Type", LaserRangeFinder_Custom, GetParameterManager());
04114       m_pType->DefineEnumValue(LaserRangeFinder_Custom, "Custom");
04115       m_pType->DefineEnumValue(LaserRangeFinder_Sick_LMS100, "Sick_LMS100");
04116       m_pType->DefineEnumValue(LaserRangeFinder_Sick_LMS200, "Sick_LMS200");
04117       m_pType->DefineEnumValue(LaserRangeFinder_Sick_LMS291, "Sick_LMS291");
04118       m_pType->DefineEnumValue(LaserRangeFinder_Hokuyo_UTM_30LX, "Hokuyo_UTM_30LX");
04119       m_pType->DefineEnumValue(LaserRangeFinder_Hokuyo_URG_04LX, "Hokuyo_URG_04LX");
04120     }
04121 
04126     void Update()
04127     {
04128       m_NumberOfRangeReadings = static_cast<kt_int32u>(math::Round((GetMaximumAngle() -
04129                                                                     GetMinimumAngle())
04130                                                                     / GetAngularResolution()) + 1);
04131     }
04132 
04133   private:
04134     LaserRangeFinder(const LaserRangeFinder&);
04135     const LaserRangeFinder& operator=(const LaserRangeFinder&);
04136 
04137   private:
04138     // sensor m_Parameters
04139     Parameter<kt_double>* m_pMinimumAngle;
04140     Parameter<kt_double>* m_pMaximumAngle;
04141 
04142     Parameter<kt_double>* m_pAngularResolution;
04143 
04144     Parameter<kt_double>* m_pMinimumRange;
04145     Parameter<kt_double>* m_pMaximumRange;
04146 
04147     Parameter<kt_double>* m_pRangeThreshold;
04148 
04149     ParameterEnum* m_pType;
04150 
04151     kt_int32u m_NumberOfRangeReadings;
04152 
04153     // static std::string LaserRangeFinderTypeNames[6];
04154   };  // LaserRangeFinder
04155 
04159 
04163   typedef enum
04164   {
04165     GridStates_Unknown = 0,
04166     GridStates_Occupied = 100,
04167     GridStates_Free = 255
04168   } GridStates;
04169 
04173 
04179   class CoordinateConverter
04180   {
04181   public:
04185     CoordinateConverter()
04186       : m_Scale(20.0)
04187     {
04188     }
04189 
04190   public:
04196     inline kt_double Transform(kt_double value)
04197     {
04198       return value * m_Scale;
04199     }
04200 
04207     inline Vector2<kt_int32s> WorldToGrid(const Vector2<kt_double>& rWorld, kt_bool flipY = false) const
04208     {
04209       kt_double gridX = (rWorld.GetX() - m_Offset.GetX()) * m_Scale;
04210       kt_double gridY = 0.0;
04211 
04212       if (flipY == false)
04213       {
04214         gridY = (rWorld.GetY() - m_Offset.GetY()) * m_Scale;
04215       }
04216       else
04217       {
04218         gridY = (m_Size.GetHeight() / m_Scale - rWorld.GetY() + m_Offset.GetY()) * m_Scale;
04219       }
04220 
04221       return Vector2<kt_int32s>(static_cast<kt_int32s>(math::Round(gridX)), static_cast<kt_int32s>(math::Round(gridY)));
04222     }
04223 
04230     inline Vector2<kt_double> GridToWorld(const Vector2<kt_int32s>& rGrid, kt_bool flipY = false) const
04231     {
04232       kt_double worldX = m_Offset.GetX() + rGrid.GetX() / m_Scale;
04233       kt_double worldY = 0.0;
04234 
04235       if (flipY == false)
04236       {
04237         worldY = m_Offset.GetY() + rGrid.GetY() / m_Scale;
04238       }
04239       else
04240       {
04241         worldY = m_Offset.GetY() + (m_Size.GetHeight() - rGrid.GetY()) / m_Scale;
04242       }
04243 
04244       return Vector2<kt_double>(worldX, worldY);
04245     }
04246 
04251     inline kt_double GetScale() const
04252     {
04253       return m_Scale;
04254     }
04255 
04260     inline void SetScale(kt_double scale)
04261     {
04262       m_Scale = scale;
04263     }
04264 
04269     inline const Vector2<kt_double>& GetOffset() const
04270     {
04271       return m_Offset;
04272     }
04273 
04278     inline void SetOffset(const Vector2<kt_double>& rOffset)
04279     {
04280       m_Offset = rOffset;
04281     }
04282 
04287     inline void SetSize(const Size2<kt_int32s>& rSize)
04288     {
04289       m_Size = rSize;
04290     }
04291 
04296     inline const Size2<kt_int32s>& GetSize() const
04297     {
04298       return m_Size;
04299     }
04300 
04305     inline kt_double GetResolution() const
04306     {
04307       return 1.0 / m_Scale;
04308     }
04309 
04314     inline void SetResolution(kt_double resolution)
04315     {
04316       m_Scale = 1.0 / resolution;
04317     }
04318 
04323     inline BoundingBox2 GetBoundingBox() const
04324     {
04325       BoundingBox2 box;
04326 
04327       kt_double minX = GetOffset().GetX();
04328       kt_double minY = GetOffset().GetY();
04329       kt_double maxX = minX + GetSize().GetWidth() * GetResolution();
04330       kt_double maxY = minY + GetSize().GetHeight() * GetResolution();
04331 
04332       box.SetMinimum(GetOffset());
04333       box.SetMaximum(Vector2<kt_double>(maxX, maxY));
04334       return box;
04335     }
04336 
04337   private:
04338     Size2<kt_int32s> m_Size;
04339     kt_double m_Scale;
04340 
04341     Vector2<kt_double> m_Offset;
04342   };  // CoordinateConverter
04343 
04347 
04351   template<typename T>
04352   class Grid
04353   {
04354   public:
04362     static Grid* CreateGrid(kt_int32s width, kt_int32s height, kt_double resolution)
04363     {
04364       Grid* pGrid = new Grid(width, height);
04365 
04366       pGrid->GetCoordinateConverter()->SetScale(1.0 / resolution);
04367 
04368       return pGrid;
04369     }
04370 
04374     virtual ~Grid()
04375     {
04376       delete [] m_pData;
04377       delete m_pCoordinateConverter;
04378     }
04379 
04380   public:
04384     void Clear()
04385     {
04386       memset(m_pData, 0, GetDataSize() * sizeof(T));
04387     }
04388 
04393     Grid* Clone()
04394     {
04395       Grid* pGrid = CreateGrid(GetWidth(), GetHeight(), GetResolution());
04396       pGrid->GetCoordinateConverter()->SetOffset(GetCoordinateConverter()->GetOffset());
04397 
04398       memcpy(pGrid->GetDataPointer(), GetDataPointer(), GetDataSize());
04399 
04400       return pGrid;
04401     }
04402 
04408     virtual void Resize(kt_int32s width, kt_int32s height)
04409     {
04410       m_Width = width;
04411       m_Height = height;
04412       m_WidthStep = math::AlignValue<kt_int32s>(width, 8);
04413 
04414       if (m_pData != NULL)
04415       {
04416         delete[] m_pData;
04417         m_pData = NULL;
04418       }
04419 
04420       try
04421       {
04422         m_pData = new T[GetDataSize()];
04423 
04424         if (m_pCoordinateConverter == NULL)
04425         {
04426           m_pCoordinateConverter = new CoordinateConverter();
04427         }
04428 
04429         m_pCoordinateConverter->SetSize(Size2<kt_int32s>(width, height));
04430       }
04431       catch(...)
04432       {
04433         m_pData = NULL;
04434 
04435         m_Width = 0;
04436         m_Height = 0;
04437         m_WidthStep = 0;
04438       }
04439 
04440       Clear();
04441     }
04442 
04447     inline kt_bool IsValidGridIndex(const Vector2<kt_int32s>& rGrid) const
04448     {
04449       return (math::IsUpTo(rGrid.GetX(), m_Width) && math::IsUpTo(rGrid.GetY(), m_Height));
04450     }
04451 
04458     virtual kt_int32s GridIndex(const Vector2<kt_int32s>& rGrid, kt_bool boundaryCheck = true) const
04459     {
04460       if (boundaryCheck == true)
04461       {
04462         if (IsValidGridIndex(rGrid) == false)
04463         {
04464           std::stringstream error;
04465           error << "Index " << rGrid << " out of range.  Index must be between [0; "
04466                 << m_Width << ") and [0; " << m_Height << ")";
04467           throw Exception(error.str());
04468         }
04469       }
04470 
04471       kt_int32s index = rGrid.GetX() + (rGrid.GetY() * m_WidthStep);
04472 
04473       if (boundaryCheck == true)
04474       {
04475         assert(math::IsUpTo(index, GetDataSize()));
04476       }
04477 
04478       return index;
04479     }
04480 
04486     Vector2<kt_int32s> IndexToGrid(kt_int32s index) const
04487     {
04488       Vector2<kt_int32s> grid;
04489 
04490       grid.SetY(index / m_WidthStep);
04491       grid.SetX(index - grid.GetY() * m_WidthStep);
04492 
04493       return grid;
04494     }
04495 
04502     inline Vector2<kt_int32s> WorldToGrid(const Vector2<kt_double>& rWorld, kt_bool flipY = false) const
04503     {
04504       return GetCoordinateConverter()->WorldToGrid(rWorld, flipY);
04505     }
04506 
04513     inline Vector2<kt_double> GridToWorld(const Vector2<kt_int32s>& rGrid, kt_bool flipY = false) const
04514     {
04515       return GetCoordinateConverter()->GridToWorld(rGrid, flipY);
04516     }
04517 
04523     T* GetDataPointer(const Vector2<kt_int32s>& rGrid)
04524     {
04525       kt_int32s index = GridIndex(rGrid, true);
04526       return m_pData + index;
04527     }
04528 
04534     T* GetDataPointer(const Vector2<kt_int32s>& rGrid) const
04535     {
04536       kt_int32s index = GridIndex(rGrid, true);
04537       return m_pData + index;
04538     }
04539 
04544     inline kt_int32s GetWidth() const
04545     {
04546       return m_Width;
04547     };
04548 
04553     inline kt_int32s GetHeight() const
04554     {
04555       return m_Height;
04556     };
04557 
04562     inline const Size2<kt_int32s> GetSize() const
04563     {
04564       return Size2<kt_int32s>(m_Width, m_Height);
04565     }
04566 
04571     inline kt_int32s GetWidthStep() const
04572     {
04573       return m_WidthStep;
04574     }
04575 
04580     inline T* GetDataPointer()
04581     {
04582       return m_pData;
04583     }
04584 
04589     inline T* GetDataPointer() const
04590     {
04591       return m_pData;
04592     }
04593 
04598     inline kt_int32s GetDataSize() const
04599     {
04600       return m_WidthStep * m_Height;
04601     }
04602 
04608     inline T GetValue(const Vector2<kt_int32s>& rGrid) const
04609     {
04610       kt_int32s index = GridIndex(rGrid);
04611       return m_pData[index];
04612     }
04613 
04618     inline CoordinateConverter* GetCoordinateConverter() const
04619     {
04620       return m_pCoordinateConverter;
04621     }
04622 
04627     inline kt_double GetResolution() const
04628     {
04629       return GetCoordinateConverter()->GetResolution();
04630     }
04631 
04636     inline BoundingBox2 GetBoundingBox() const
04637     {
04638       return GetCoordinateConverter()->GetBoundingBox();
04639     }
04640 
04650     void TraceLine(kt_int32s x0, kt_int32s y0, kt_int32s x1, kt_int32s y1, Functor* f = NULL)
04651     {
04652       kt_bool steep = abs(y1 - y0) > abs(x1 - x0);
04653       if (steep)
04654       {
04655         std::swap(x0, y0);
04656         std::swap(x1, y1);
04657       }
04658       if (x0 > x1)
04659       {
04660         std::swap(x0, x1);
04661         std::swap(y0, y1);
04662       }
04663 
04664       kt_int32s deltaX = x1 - x0;
04665       kt_int32s deltaY = abs(y1 - y0);
04666       kt_int32s error = 0;
04667       kt_int32s ystep;
04668       kt_int32s y = y0;
04669 
04670       if (y0 < y1)
04671       {
04672         ystep = 1;
04673       }
04674       else
04675       {
04676         ystep = -1;
04677       }
04678 
04679       kt_int32s pointX;
04680       kt_int32s pointY;
04681       for (kt_int32s x = x0; x <= x1; x++)
04682       {
04683         if (steep)
04684         {
04685           pointX = y;
04686           pointY = x;
04687         }
04688         else
04689         {
04690           pointX = x;
04691           pointY = y;
04692         }
04693 
04694         error += deltaY;
04695 
04696         if (2 * error >= deltaX)
04697         {
04698           y += ystep;
04699           error -= deltaX;
04700         }
04701 
04702         Vector2<kt_int32s> gridIndex(pointX, pointY);
04703         if (IsValidGridIndex(gridIndex))
04704         {
04705           kt_int32s index = GridIndex(gridIndex, false);
04706           T* pGridPointer = GetDataPointer();
04707           pGridPointer[index]++;
04708 
04709           if (f != NULL)
04710           {
04711             (*f)(index);
04712           }
04713         }
04714       }
04715     }
04716 
04717   protected:
04723     Grid(kt_int32s width, kt_int32s height)
04724       : m_pData(NULL)
04725       , m_pCoordinateConverter(NULL)
04726     {
04727       Resize(width, height);
04728     }
04729 
04730   private:
04731     kt_int32s m_Width;       // width of grid
04732     kt_int32s m_Height;      // height of grid
04733     kt_int32s m_WidthStep;   // 8 bit aligned width of grid
04734     T* m_pData;              // grid data
04735 
04736     // coordinate converter to convert between world coordinates and grid coordinates
04737     CoordinateConverter* m_pCoordinateConverter;
04738   };  // Grid
04739 
04743 
04747   class CustomData : public Object
04748   {
04749   public:
04750     // @cond EXCLUDE
04751     KARTO_Object(CustomData)
04752     // @endcond
04753 
04754   public:
04758     CustomData()
04759       : Object()
04760     {
04761     }
04762 
04766     virtual ~CustomData()
04767     {
04768     }
04769 
04770   public:
04775     virtual const std::string Write() const = 0;
04776 
04781     virtual void Read(const std::string& rValue) = 0;
04782 
04783   private:
04784     CustomData(const CustomData&);
04785     const CustomData& operator=(const CustomData&);
04786   };
04787 
04791   typedef std::vector<CustomData*> CustomDataVector;
04792 
04796 
04800   class KARTO_EXPORT SensorData : public Object
04801   {
04802   public:
04803     // @cond EXCLUDE
04804     KARTO_Object(SensorData)
04805     // @endcond
04806 
04807   public:
04811     virtual ~SensorData();
04812 
04813   public:
04818     inline kt_int32s GetStateId() const
04819     {
04820       return m_StateId;
04821     }
04822 
04827     inline void SetStateId(kt_int32s stateId)
04828     {
04829       m_StateId = stateId;
04830     }
04831 
04836     inline kt_int32s GetUniqueId() const
04837     {
04838       return m_UniqueId;
04839     }
04840 
04845     inline void SetUniqueId(kt_int32u uniqueId)
04846     {
04847       m_UniqueId = uniqueId;
04848     }
04849 
04854     inline kt_double GetTime() const
04855     {
04856       return m_Time;
04857     }
04858 
04863     inline void SetTime(kt_double time)
04864     {
04865       m_Time = time;
04866     }
04867 
04872     inline const Name& GetSensorName() const
04873     {
04874       return m_SensorName;
04875     }
04876 
04881     inline void AddCustomData(CustomData* pCustomData)
04882     {
04883       m_CustomData.push_back(pCustomData);
04884     }
04885 
04890     inline const CustomDataVector& GetCustomData() const
04891     {
04892       return m_CustomData;
04893     }
04894 
04895   protected:
04899     SensorData(const Name& rSensorName);
04900 
04901   private:
04905     SensorData(const SensorData&);
04906 
04910     const SensorData& operator=(const SensorData&);
04911 
04912   private:
04916     kt_int32s m_StateId;
04917 
04921     kt_int32s m_UniqueId;
04922 
04926     Name m_SensorName;
04927 
04931     kt_double m_Time;
04932 
04933     CustomDataVector m_CustomData;
04934   };
04935 
04939 
04943   typedef std::vector<kt_double> RangeReadingsVector;
04944 
04948   class LaserRangeScan : public SensorData
04949   {
04950   public:
04951     // @cond EXCLUDE
04952     KARTO_Object(LaserRangeScan)
04953     // @endcond
04954 
04955   public:
04960     LaserRangeScan(const Name& rSensorName)
04961       : SensorData(rSensorName)
04962       , m_pRangeReadings(NULL)
04963       , m_NumberOfRangeReadings(0)
04964     {
04965     }
04966 
04972     LaserRangeScan(const Name& rSensorName, const RangeReadingsVector& rRangeReadings)
04973       : SensorData(rSensorName)
04974       , m_pRangeReadings(NULL)
04975       , m_NumberOfRangeReadings(0)
04976     {
04977       assert(rSensorName.ToString() != "");
04978 
04979       SetRangeReadings(rRangeReadings);
04980     }
04981 
04985     virtual ~LaserRangeScan()
04986     {
04987       delete [] m_pRangeReadings;
04988     }
04989 
04990   public:
04995     inline kt_double* GetRangeReadings() const
04996     {
04997       return m_pRangeReadings;
04998     }
04999 
05000     inline RangeReadingsVector GetRangeReadingsVector() const
05001     {
05002       return RangeReadingsVector(m_pRangeReadings, m_pRangeReadings + m_NumberOfRangeReadings);
05003     }
05004 
05009     inline void SetRangeReadings(const RangeReadingsVector& rRangeReadings)
05010     {
05011       // ignore for now! XXXMAE BUGUBUG 05/21/2010 << TODO(lucbettaieb): What the heck is this??
05012       // if (rRangeReadings.size() != GetNumberOfRangeReadings())
05013       // {
05014       //   std::stringstream error;
05015       //   error << "Given number of readings (" << rRangeReadings.size()
05016       //         << ") does not match expected number of range finder (" << GetNumberOfRangeReadings() << ")";
05017       //   throw Exception(error.str());
05018       // }
05019 
05020       if (!rRangeReadings.empty())
05021       {
05022         if (rRangeReadings.size() != m_NumberOfRangeReadings)
05023         {
05024           // delete old readings
05025           delete [] m_pRangeReadings;
05026 
05027           // store size of array!
05028           m_NumberOfRangeReadings = static_cast<kt_int32u>(rRangeReadings.size());
05029 
05030           // allocate range readings
05031           m_pRangeReadings = new kt_double[m_NumberOfRangeReadings];
05032         }
05033 
05034         // copy readings
05035         kt_int32u index = 0;
05036         const_forEach(RangeReadingsVector, &rRangeReadings)
05037         {
05038           m_pRangeReadings[index++] = *iter;
05039         }
05040       }
05041       else
05042       {
05043         delete [] m_pRangeReadings;
05044         m_pRangeReadings = NULL;
05045       }
05046     }
05047 
05052     inline LaserRangeFinder* GetLaserRangeFinder() const
05053     {
05054       return SensorManager::GetInstance()->GetSensorByName<LaserRangeFinder>(GetSensorName());
05055     }
05056 
05061     inline kt_int32u GetNumberOfRangeReadings() const
05062     {
05063       return m_NumberOfRangeReadings;
05064     }
05065 
05066   private:
05067     LaserRangeScan(const LaserRangeScan&);
05068     const LaserRangeScan& operator=(const LaserRangeScan&);
05069 
05070   private:
05071     kt_double* m_pRangeReadings;
05072     kt_int32u m_NumberOfRangeReadings;
05073   };  // LaserRangeScan
05074 
05078 
05082   class DrivePose : public SensorData
05083   {
05084   public:
05085     // @cond EXCLUDE
05086     KARTO_Object(DrivePose)
05087     // @endcond
05088 
05089   public:
05094     DrivePose(const Name& rSensorName)
05095       : SensorData(rSensorName)
05096     {
05097     }
05098 
05102     virtual ~DrivePose()
05103     {
05104     }
05105 
05106   public:
05111     inline const Pose3& GetOdometricPose() const
05112     {
05113       return m_OdometricPose;
05114     }
05115 
05120     inline void SetOdometricPose(const Pose3& rPose)
05121     {
05122       m_OdometricPose = rPose;
05123     }
05124 
05125   private:
05126     DrivePose(const DrivePose&);
05127     const DrivePose& operator=(const DrivePose&);
05128 
05129   private:
05133     Pose3 m_OdometricPose;
05134   };  // class DrivePose
05135 
05139 
05146   class LocalizedRangeScan : public LaserRangeScan
05147   {
05148   public:
05149     // @cond EXCLUDE
05150     KARTO_Object(LocalizedRangeScan)
05151     // @endcond
05152 
05153   public:
05157     LocalizedRangeScan(const Name& rSensorName, const RangeReadingsVector& rReadings)
05158       : LaserRangeScan(rSensorName, rReadings)
05159       , m_IsDirty(true)
05160     {
05161     }
05162 
05166     virtual ~LocalizedRangeScan()
05167     {
05168     }
05169 
05170   private:
05171     mutable boost::shared_mutex m_Lock;
05172 
05173   public:
05178     inline const Pose2& GetOdometricPose() const
05179     {
05180       return m_OdometricPose;
05181     }
05182 
05187     inline void SetOdometricPose(const Pose2& rPose)
05188     {
05189       m_OdometricPose = rPose;
05190     }
05191 
05200     inline const Pose2& GetCorrectedPose() const
05201     {
05202       return m_CorrectedPose;
05203     }
05204 
05209     inline void SetCorrectedPose(const Pose2& rPose)
05210     {
05211       m_CorrectedPose = rPose;
05212 
05213       m_IsDirty = true;
05214     }
05215 
05219     inline const Pose2& GetBarycenterPose() const
05220     {
05221       boost::shared_lock<boost::shared_mutex> lock(m_Lock);
05222       if (m_IsDirty)
05223       {
05224         // throw away constness and do an update!
05225         lock.unlock();
05226         boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
05227         const_cast<LocalizedRangeScan*>(this)->Update();
05228       }
05229 
05230       return m_BarycenterPose;
05231     }
05232 
05238     inline Pose2 GetReferencePose(kt_bool useBarycenter) const
05239     {
05240       boost::shared_lock<boost::shared_mutex> lock(m_Lock);
05241       if (m_IsDirty)
05242       {
05243         // throw away constness and do an update!
05244         lock.unlock();
05245         boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
05246         const_cast<LocalizedRangeScan*>(this)->Update();
05247       }
05248 
05249       return useBarycenter ? GetBarycenterPose() : GetSensorPose();
05250     }
05251 
05256     inline Pose2 GetSensorPose() const
05257     {
05258       return GetSensorAt(m_CorrectedPose);
05259     }
05260 
05265     void SetSensorPose(const Pose2& rScanPose)
05266     {
05267       Pose2 deviceOffsetPose2 = GetLaserRangeFinder()->GetOffsetPose();
05268       kt_double offsetLength = deviceOffsetPose2.GetPosition().Length();
05269       kt_double offsetHeading = deviceOffsetPose2.GetHeading();
05270       kt_double angleoffset = atan2(deviceOffsetPose2.GetY(), deviceOffsetPose2.GetX());
05271       kt_double correctedHeading = math::NormalizeAngle(rScanPose.GetHeading());
05272       Pose2 worldSensorOffset = Pose2(offsetLength * cos(correctedHeading + angleoffset - offsetHeading),
05273                                       offsetLength * sin(correctedHeading + angleoffset - offsetHeading),
05274                                       offsetHeading);
05275 
05276       m_CorrectedPose = rScanPose - worldSensorOffset;
05277 
05278       Update();
05279     }
05280 
05286     inline Pose2 GetSensorAt(const Pose2& rPose) const
05287     {
05288       return Transform(rPose).TransformPose(GetLaserRangeFinder()->GetOffsetPose());
05289     }
05290 
05295     inline const BoundingBox2& GetBoundingBox() const
05296     {
05297       boost::shared_lock<boost::shared_mutex> lock(m_Lock);
05298       if (m_IsDirty)
05299       {
05300         // throw away constness and do an update!
05301         lock.unlock();
05302         boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
05303         const_cast<LocalizedRangeScan*>(this)->Update();
05304       }
05305 
05306       return m_BoundingBox;
05307     }
05308 
05312     inline const PointVectorDouble& GetPointReadings(kt_bool wantFiltered = false) const
05313     {
05314       boost::shared_lock<boost::shared_mutex> lock(m_Lock);
05315       if (m_IsDirty)
05316       {
05317         // throw away constness and do an update!
05318         lock.unlock();
05319         boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
05320         const_cast<LocalizedRangeScan*>(this)->Update();
05321       }
05322 
05323       if (wantFiltered == true)
05324       {
05325         return m_PointReadings;
05326       }
05327       else
05328       {
05329         return m_UnfilteredPointReadings;
05330       }
05331     }
05332 
05333   private:
05338     void Update()
05339     {
05340       LaserRangeFinder* pLaserRangeFinder = GetLaserRangeFinder();
05341 
05342       if (pLaserRangeFinder != NULL)
05343       {
05344         m_PointReadings.clear();
05345         m_UnfilteredPointReadings.clear();
05346 
05347         kt_double rangeThreshold = pLaserRangeFinder->GetRangeThreshold();
05348         kt_double minimumAngle = pLaserRangeFinder->GetMinimumAngle();
05349         kt_double angularResolution = pLaserRangeFinder->GetAngularResolution();
05350         Pose2 scanPose = GetSensorPose();
05351 
05352         // compute point readings
05353         Vector2<kt_double> rangePointsSum;
05354         kt_int32u beamNum = 0;
05355         for (kt_int32u i = 0; i < pLaserRangeFinder->GetNumberOfRangeReadings(); i++, beamNum++)
05356         {
05357           kt_double rangeReading = GetRangeReadings()[i];
05358           if (!math::InRange(rangeReading, pLaserRangeFinder->GetMinimumRange(), rangeThreshold))
05359           {
05360             kt_double angle = scanPose.GetHeading() + minimumAngle + beamNum * angularResolution;
05361 
05362             Vector2<kt_double> point;
05363             point.SetX(scanPose.GetX() + (rangeReading * cos(angle)));
05364             point.SetY(scanPose.GetY() + (rangeReading * sin(angle)));
05365 
05366             m_UnfilteredPointReadings.push_back(point);
05367             continue;
05368           }
05369 
05370           kt_double angle = scanPose.GetHeading() + minimumAngle + beamNum * angularResolution;
05371 
05372           Vector2<kt_double> point;
05373           point.SetX(scanPose.GetX() + (rangeReading * cos(angle)));
05374           point.SetY(scanPose.GetY() + (rangeReading * sin(angle)));
05375 
05376           m_PointReadings.push_back(point);
05377           m_UnfilteredPointReadings.push_back(point);
05378 
05379           rangePointsSum += point;
05380         }
05381 
05382         // compute barycenter
05383         kt_double nPoints = static_cast<kt_double>(m_PointReadings.size());
05384         if (nPoints != 0.0)
05385         {
05386           Vector2<kt_double> averagePosition = Vector2<kt_double>(rangePointsSum / nPoints);
05387           m_BarycenterPose = Pose2(averagePosition, 0.0);
05388         }
05389         else
05390         {
05391           m_BarycenterPose = scanPose;
05392         }
05393 
05394         // calculate bounding box of scan
05395         m_BoundingBox = BoundingBox2();
05396         m_BoundingBox.Add(scanPose.GetPosition());
05397         forEach(PointVectorDouble, &m_PointReadings)
05398         {
05399           m_BoundingBox.Add(*iter);
05400         }
05401       }
05402 
05403       m_IsDirty = false;
05404     }
05405 
05406   private:
05407     LocalizedRangeScan(const LocalizedRangeScan&);
05408     const LocalizedRangeScan& operator=(const LocalizedRangeScan&);
05409 
05410   private:
05414     Pose2 m_OdometricPose;
05415 
05419     Pose2 m_CorrectedPose;
05420 
05424     Pose2 m_BarycenterPose;
05425 
05429     PointVectorDouble m_PointReadings;
05430 
05434     PointVectorDouble m_UnfilteredPointReadings;
05435 
05439     BoundingBox2 m_BoundingBox;
05440 
05444     kt_bool m_IsDirty;
05445   };  // LocalizedRangeScan
05446 
05450   typedef std::vector<LocalizedRangeScan*> LocalizedRangeScanVector;
05451 
05455 
05456   class OccupancyGrid;
05457 
05458   class KARTO_EXPORT CellUpdater : public Functor
05459   {
05460   public:
05461     CellUpdater(OccupancyGrid* pGrid)
05462       : m_pOccupancyGrid(pGrid)
05463     {
05464     }
05465 
05470     virtual void operator() (kt_int32u index);
05471 
05472   private:
05473     OccupancyGrid* m_pOccupancyGrid;
05474   };  // CellUpdater
05475 
05479   class OccupancyGrid : public Grid<kt_int8u>
05480   {
05481     friend class CellUpdater;
05482     friend class IncrementalOccupancyGrid;
05483 
05484   public:
05492     OccupancyGrid(kt_int32s width, kt_int32s height, const Vector2<kt_double>& rOffset, kt_double resolution)
05493       : Grid<kt_int8u>(width, height)
05494       , m_pCellPassCnt(Grid<kt_int32u>::CreateGrid(0, 0, resolution))
05495       , m_pCellHitsCnt(Grid<kt_int32u>::CreateGrid(0, 0, resolution))
05496       , m_pCellUpdater(NULL)
05497     {
05498       m_pCellUpdater = new CellUpdater(this);
05499 
05500       if (karto::math::DoubleEqual(resolution, 0.0))
05501       {
05502         throw Exception("Resolution cannot be 0");
05503       }
05504 
05505       m_pMinPassThrough = new Parameter<kt_int32u>("MinPassThrough", 2);
05506       m_pOccupancyThreshold = new Parameter<kt_double>("OccupancyThreshold", 0.1);
05507 
05508       GetCoordinateConverter()->SetScale(1.0 / resolution);
05509       GetCoordinateConverter()->SetOffset(rOffset);
05510     }
05511 
05515     virtual ~OccupancyGrid()
05516     {
05517       delete m_pCellUpdater;
05518 
05519       delete m_pCellPassCnt;
05520       delete m_pCellHitsCnt;
05521 
05522       delete m_pMinPassThrough;
05523       delete m_pOccupancyThreshold;
05524     }
05525 
05526   public:
05532     static OccupancyGrid* CreateFromScans(const LocalizedRangeScanVector& rScans, kt_double resolution)
05533     {
05534       if (rScans.empty())
05535       {
05536         return NULL;
05537       }
05538 
05539       kt_int32s width, height;
05540       Vector2<kt_double> offset;
05541       ComputeDimensions(rScans, resolution, width, height, offset);
05542       OccupancyGrid* pOccupancyGrid = new OccupancyGrid(width, height, offset, resolution);
05543       pOccupancyGrid->CreateFromScans(rScans);
05544 
05545       return pOccupancyGrid;
05546     }
05547 
05552     OccupancyGrid* Clone() const
05553     {
05554       OccupancyGrid* pOccupancyGrid = new OccupancyGrid(GetWidth(),
05555                                                         GetHeight(),
05556                                                         GetCoordinateConverter()->GetOffset(),
05557                                                         1.0 / GetCoordinateConverter()->GetScale());
05558       memcpy(pOccupancyGrid->GetDataPointer(), GetDataPointer(), GetDataSize());
05559 
05560       pOccupancyGrid->GetCoordinateConverter()->SetSize(GetCoordinateConverter()->GetSize());
05561       pOccupancyGrid->m_pCellPassCnt = m_pCellPassCnt->Clone();
05562       pOccupancyGrid->m_pCellHitsCnt = m_pCellHitsCnt->Clone();
05563 
05564       return pOccupancyGrid;
05565     }
05566 
05572     virtual kt_bool IsFree(const Vector2<kt_int32s>& rPose) const
05573     {
05574       kt_int8u* pOffsets = reinterpret_cast<kt_int8u*>(GetDataPointer(rPose));
05575       if (*pOffsets == GridStates_Free)
05576       {
05577         return true;
05578       }
05579 
05580       return false;
05581     }
05582 
05590     virtual kt_double RayCast(const Pose2& rPose2, kt_double maxRange) const
05591     {
05592       double scale = GetCoordinateConverter()->GetScale();
05593 
05594       kt_double x = rPose2.GetX();
05595       kt_double y = rPose2.GetY();
05596       kt_double theta = rPose2.GetHeading();
05597 
05598       kt_double sinTheta = sin(theta);
05599       kt_double cosTheta = cos(theta);
05600 
05601       kt_double xStop = x + maxRange * cosTheta;
05602       kt_double xSteps = 1 + fabs(xStop - x) * scale;
05603 
05604       kt_double yStop = y + maxRange * sinTheta;
05605       kt_double ySteps = 1 + fabs(yStop - y) * scale;
05606 
05607       kt_double steps = math::Maximum(xSteps, ySteps);
05608       kt_double delta = maxRange / steps;
05609       kt_double distance = delta;
05610 
05611       for (kt_int32u i = 1; i < steps; i++)
05612       {
05613         kt_double x1 = x + distance * cosTheta;
05614         kt_double y1 = y + distance * sinTheta;
05615 
05616         Vector2<kt_int32s> gridIndex = WorldToGrid(Vector2<kt_double>(x1, y1));
05617         if (IsValidGridIndex(gridIndex) && IsFree(gridIndex))
05618         {
05619           distance = (i + 1) * delta;
05620         }
05621         else
05622         {
05623           break;
05624         }
05625       }
05626 
05627       return (distance < maxRange)? distance : maxRange;
05628     }
05629 
05635     void SetMinPassThrough(kt_int32u count)
05636     {
05637       m_pMinPassThrough->SetValue(count);
05638     }
05639 
05644     void SetOccupancyThreshold(kt_double thresh)
05645     {
05646       m_pOccupancyThreshold->SetValue(thresh);
05647     }
05648 
05649   protected:
05654     virtual Grid<kt_int32u>* GetCellHitsCounts()
05655     {
05656       return m_pCellHitsCnt;
05657     }
05658 
05663     virtual Grid<kt_int32u>* GetCellPassCounts()
05664     {
05665       return m_pCellPassCnt;
05666     }
05667 
05668   protected:
05677     static void ComputeDimensions(const LocalizedRangeScanVector& rScans,
05678                                   kt_double resolution,
05679                                   kt_int32s& rWidth,
05680                                   kt_int32s& rHeight,
05681                                   Vector2<kt_double>& rOffset)
05682     {
05683       BoundingBox2 boundingBox;
05684       const_forEach(LocalizedRangeScanVector, &rScans)
05685       {
05686         boundingBox.Add((*iter)->GetBoundingBox());
05687       }
05688 
05689       kt_double scale = 1.0 / resolution;
05690       Size2<kt_double> size = boundingBox.GetSize();
05691 
05692       rWidth = static_cast<kt_int32s>(math::Round(size.GetWidth() * scale));
05693       rHeight = static_cast<kt_int32s>(math::Round(size.GetHeight() * scale));
05694       rOffset = boundingBox.GetMinimum();
05695     }
05696 
05701     virtual void CreateFromScans(const LocalizedRangeScanVector& rScans)
05702     {
05703       m_pCellPassCnt->Resize(GetWidth(), GetHeight());
05704       m_pCellPassCnt->GetCoordinateConverter()->SetOffset(GetCoordinateConverter()->GetOffset());
05705 
05706       m_pCellHitsCnt->Resize(GetWidth(), GetHeight());
05707       m_pCellHitsCnt->GetCoordinateConverter()->SetOffset(GetCoordinateConverter()->GetOffset());
05708 
05709       const_forEach(LocalizedRangeScanVector, &rScans)
05710       {
05711         LocalizedRangeScan* pScan = *iter;
05712         AddScan(pScan);
05713       }
05714 
05715       Update();
05716     }
05717 
05725     virtual kt_bool AddScan(LocalizedRangeScan* pScan, kt_bool doUpdate = false)
05726     {
05727       kt_double rangeThreshold = pScan->GetLaserRangeFinder()->GetRangeThreshold();
05728       kt_double maxRange = pScan->GetLaserRangeFinder()->GetMaximumRange();
05729 
05730       Vector2<kt_double> scanPosition = pScan->GetSensorPose().GetPosition();
05731 
05732       // get scan point readings
05733       const PointVectorDouble& rPointReadings = pScan->GetPointReadings(false);
05734 
05735       kt_bool isAllInMap = true;
05736 
05737       // draw lines from scan position to all point readings
05738       int pointIndex = 0;
05739       const_forEachAs(PointVectorDouble, &rPointReadings, pointsIter)
05740       {
05741         Vector2<kt_double> point = *pointsIter;
05742         kt_double rangeReading = pScan->GetRangeReadings()[pointIndex];
05743         kt_bool isEndPointValid = rangeReading < (rangeThreshold - KT_TOLERANCE);
05744 
05745         if (rangeReading >= maxRange || isnan(rangeReading))
05746         {
05747           // ignore max range readings
05748           pointIndex++;
05749           continue;
05750         }
05751         else if (rangeReading >= rangeThreshold)
05752         {
05753           // trace up to range reading
05754           kt_double ratio = rangeThreshold / rangeReading;
05755           kt_double dx = point.GetX() - scanPosition.GetX();
05756           kt_double dy = point.GetY() - scanPosition.GetY();
05757           point.SetX(scanPosition.GetX() + ratio * dx);
05758           point.SetY(scanPosition.GetY() + ratio * dy);
05759         }
05760 
05761         kt_bool isInMap = RayTrace(scanPosition, point, isEndPointValid, doUpdate);
05762         if (!isInMap)
05763         {
05764           isAllInMap = false;
05765         }
05766 
05767         pointIndex++;
05768       }
05769 
05770       return isAllInMap;
05771     }
05772 
05782     virtual kt_bool RayTrace(const Vector2<kt_double>& rWorldFrom,
05783                              const Vector2<kt_double>& rWorldTo,
05784                              kt_bool isEndPointValid,
05785                              kt_bool doUpdate = false)
05786     {
05787       assert(m_pCellPassCnt != NULL && m_pCellHitsCnt != NULL);
05788 
05789       Vector2<kt_int32s> gridFrom = m_pCellPassCnt->WorldToGrid(rWorldFrom);
05790       Vector2<kt_int32s> gridTo = m_pCellPassCnt->WorldToGrid(rWorldTo);
05791 
05792       CellUpdater* pCellUpdater = doUpdate ? m_pCellUpdater : NULL;
05793       m_pCellPassCnt->TraceLine(gridFrom.GetX(), gridFrom.GetY(), gridTo.GetX(), gridTo.GetY(), pCellUpdater);
05794 
05795       // for the end point
05796       if (isEndPointValid)
05797       {
05798         if (m_pCellPassCnt->IsValidGridIndex(gridTo))
05799         {
05800           kt_int32s index = m_pCellPassCnt->GridIndex(gridTo, false);
05801 
05802           kt_int32u* pCellPassCntPtr = m_pCellPassCnt->GetDataPointer();
05803           kt_int32u* pCellHitCntPtr = m_pCellHitsCnt->GetDataPointer();
05804 
05805           // increment cell pass through and hit count
05806           pCellPassCntPtr[index]++;
05807           pCellHitCntPtr[index]++;
05808 
05809           if (doUpdate)
05810           {
05811             (*m_pCellUpdater)(index);
05812           }
05813         }
05814       }
05815 
05816       return m_pCellPassCnt->IsValidGridIndex(gridTo);
05817     }
05818 
05825     virtual void UpdateCell(kt_int8u* pCell, kt_int32u cellPassCnt, kt_int32u cellHitCnt)
05826     {
05827       if (cellPassCnt > m_pMinPassThrough->GetValue())
05828       {
05829         kt_double hitRatio = static_cast<kt_double>(cellHitCnt) / static_cast<kt_double>(cellPassCnt);
05830 
05831         if (hitRatio > m_pOccupancyThreshold->GetValue())
05832         {
05833           *pCell = GridStates_Occupied;
05834         }
05835         else
05836         {
05837           *pCell = GridStates_Free;
05838         }
05839       }
05840     }
05841 
05845     virtual void Update()
05846     {
05847       assert(m_pCellPassCnt != NULL && m_pCellHitsCnt != NULL);
05848 
05849       // clear grid
05850       Clear();
05851 
05852       // set occupancy status of cells
05853       kt_int8u* pDataPtr = GetDataPointer();
05854       kt_int32u* pCellPassCntPtr = m_pCellPassCnt->GetDataPointer();
05855       kt_int32u* pCellHitCntPtr = m_pCellHitsCnt->GetDataPointer();
05856 
05857       kt_int32u nBytes = GetDataSize();
05858       for (kt_int32u i = 0; i < nBytes; i++, pDataPtr++, pCellPassCntPtr++, pCellHitCntPtr++)
05859       {
05860         UpdateCell(pDataPtr, *pCellPassCntPtr, *pCellHitCntPtr);
05861       }
05862     }
05863 
05869     virtual void Resize(kt_int32s width, kt_int32s height)
05870     {
05871       Grid<kt_int8u>::Resize(width, height);
05872       m_pCellPassCnt->Resize(width, height);
05873       m_pCellHitsCnt->Resize(width, height);
05874     }
05875 
05876   protected:
05880     Grid<kt_int32u>* m_pCellPassCnt;
05881 
05885     Grid<kt_int32u>* m_pCellHitsCnt;
05886 
05887   private:
05891     OccupancyGrid(const OccupancyGrid&);
05892 
05896     const OccupancyGrid& operator=(const OccupancyGrid&);
05897 
05898   private:
05899     CellUpdater* m_pCellUpdater;
05900 
05902     // NOTE: These two values are dependent on the resolution.  If the resolution is too small,
05903     // then not many beams will hit the cell!
05904 
05905     // Number of beams that must pass through a cell before it will be considered to be occupied
05906     // or unoccupied.  This prevents stray beams from messing up the map.
05907     Parameter<kt_int32u>* m_pMinPassThrough;
05908 
05909     // Minimum ratio of beams hitting cell to beams passing through cell for cell to be marked as occupied
05910     Parameter<kt_double>* m_pOccupancyThreshold;
05911   };  // OccupancyGrid
05912 
05916 
05921   class DatasetInfo : public Object
05922   {
05923   public:
05924     // @cond EXCLUDE
05925     KARTO_Object(DatasetInfo)
05926     // @endcond
05927 
05928   public:
05929     DatasetInfo()
05930       : Object()
05931     {
05932       m_pTitle = new Parameter<std::string>("Title", "", GetParameterManager());
05933       m_pAuthor = new Parameter<std::string>("Author", "", GetParameterManager());
05934       m_pDescription = new Parameter<std::string>("Description", "", GetParameterManager());
05935       m_pCopyright = new Parameter<std::string>("Copyright", "", GetParameterManager());
05936     }
05937 
05938     virtual ~DatasetInfo()
05939     {
05940     }
05941 
05942   public:
05946     const std::string& GetTitle() const
05947     {
05948       return m_pTitle->GetValue();
05949     }
05950 
05954     const std::string& GetAuthor() const
05955     {
05956       return m_pAuthor->GetValue();
05957     }
05958 
05962     const std::string& GetDescription() const
05963     {
05964       return m_pDescription->GetValue();
05965     }
05966 
05970     const std::string& GetCopyright() const
05971     {
05972       return m_pCopyright->GetValue();
05973     }
05974 
05975   private:
05976     DatasetInfo(const DatasetInfo&);
05977     const DatasetInfo& operator=(const DatasetInfo&);
05978 
05979   private:
05980     Parameter<std::string>* m_pTitle;
05981     Parameter<std::string>* m_pAuthor;
05982     Parameter<std::string>* m_pDescription;
05983     Parameter<std::string>* m_pCopyright;
05984   };  // class DatasetInfo
05985 
05989 
05994   class Dataset
05995   {
05996   public:
06000     Dataset()
06001       : m_pDatasetInfo(NULL)
06002     {
06003     }
06004 
06008     virtual ~Dataset()
06009     {
06010       Clear();
06011     }
06012 
06013   public:
06018     void Add(Object* pObject)
06019     {
06020       if (pObject != NULL)
06021       {
06022         if (dynamic_cast<Sensor*>(pObject))
06023         {
06024           Sensor* pSensor = dynamic_cast<Sensor*>(pObject);
06025           if (pSensor != NULL)
06026           {
06027             m_SensorNameLookup[pSensor->GetName()] = pSensor;
06028 
06029             karto::SensorManager::GetInstance()->RegisterSensor(pSensor);
06030           }
06031 
06032           m_Objects.push_back(pObject);
06033         }
06034         else if (dynamic_cast<SensorData*>(pObject))
06035         {
06036           SensorData* pSensorData = dynamic_cast<SensorData*>(pObject);
06037           m_Objects.push_back(pSensorData);
06038         }
06039         else if (dynamic_cast<DatasetInfo*>(pObject))
06040         {
06041           m_pDatasetInfo = dynamic_cast<DatasetInfo*>(pObject);
06042         }
06043         else
06044         {
06045           m_Objects.push_back(pObject);
06046         }
06047       }
06048     }
06049 
06054     inline const ObjectVector& GetObjects() const
06055     {
06056       return m_Objects;
06057     }
06058 
06063     inline DatasetInfo* GetDatasetInfo()
06064     {
06065       return m_pDatasetInfo;
06066     }
06067 
06071     virtual void Clear()
06072     {
06073       for (std::map<Name, Sensor*>::iterator iter = m_SensorNameLookup.begin(); iter != m_SensorNameLookup.end(); ++iter)
06074       {
06075         karto::SensorManager::GetInstance()->UnregisterSensor(iter->second);
06076       }
06077 
06078       forEach(ObjectVector, &m_Objects)
06079       {
06080         delete *iter;
06081       }
06082 
06083       m_Objects.clear();
06084 
06085       if (m_pDatasetInfo != NULL)
06086       {
06087         delete m_pDatasetInfo;
06088         m_pDatasetInfo = NULL;
06089       }
06090     }
06091 
06092   private:
06093     std::map<Name, Sensor*> m_SensorNameLookup;
06094     ObjectVector m_Objects;
06095     DatasetInfo* m_pDatasetInfo;
06096   };  // Dataset
06097 
06101 
06106   class LookupArray
06107   {
06108   public:
06112     LookupArray()
06113       : m_pArray(NULL)
06114       , m_Capacity(0)
06115       , m_Size(0)
06116     {
06117     }
06118 
06122     virtual ~LookupArray()
06123     {
06124       assert(m_pArray != NULL);
06125 
06126       delete[] m_pArray;
06127       m_pArray = NULL;
06128     }
06129 
06130   public:
06134     void Clear()
06135     {
06136       memset(m_pArray, 0, sizeof(kt_int32s) * m_Capacity);
06137     }
06138 
06143     kt_int32u GetSize() const
06144     {
06145       return m_Size;
06146     }
06147 
06152     void SetSize(kt_int32u size)
06153     {
06154       assert(size != 0);
06155 
06156       if (size > m_Capacity)
06157       {
06158         if (m_pArray != NULL)
06159         {
06160           delete [] m_pArray;
06161         }
06162         m_Capacity = size;
06163         m_pArray = new kt_int32s[m_Capacity];
06164       }
06165 
06166       m_Size = size;
06167     }
06168 
06174     inline kt_int32s& operator [] (kt_int32u index)
06175     {
06176       assert(index < m_Size);
06177 
06178       return m_pArray[index];
06179     }
06180 
06186     inline kt_int32s operator [] (kt_int32u index) const
06187     {
06188       assert(index < m_Size);
06189 
06190       return m_pArray[index];
06191     }
06192 
06197     inline kt_int32s* GetArrayPointer()
06198     {
06199       return m_pArray;
06200     }
06201 
06206     inline kt_int32s* GetArrayPointer() const
06207     {
06208       return m_pArray;
06209     }
06210 
06211   private:
06212     kt_int32s* m_pArray;
06213     kt_int32u m_Capacity;
06214     kt_int32u m_Size;
06215   };  // LookupArray
06216 
06220 
06234   template<typename T>
06235   class GridIndexLookup
06236   {
06237   public:
06242     GridIndexLookup(Grid<T>* pGrid)
06243       : m_pGrid(pGrid)
06244       , m_Capacity(0)
06245       , m_Size(0)
06246       , m_ppLookupArray(NULL)
06247     {
06248     }
06249 
06253     virtual ~GridIndexLookup()
06254     {
06255       DestroyArrays();
06256     }
06257 
06258   public:
06264     const LookupArray* GetLookupArray(kt_int32u index) const
06265     {
06266       assert(math::IsUpTo(index, m_Size));
06267 
06268       return m_ppLookupArray[index];
06269     }
06270 
06275     const std::vector<kt_double>& GetAngles() const
06276     {
06277       return m_Angles;
06278     }
06279 
06287     void ComputeOffsets(LocalizedRangeScan* pScan,
06288                         kt_double angleCenter,
06289                         kt_double angleOffset,
06290                         kt_double angleResolution)
06291     {
06292       assert(angleOffset != 0.0);
06293       assert(angleResolution != 0.0);
06294 
06295       kt_int32u nAngles = static_cast<kt_int32u>(math::Round(angleOffset * 2.0 / angleResolution) + 1);
06296       SetSize(nAngles);
06297 
06299       // convert points into local coordinates of scan pose
06300 
06301       const PointVectorDouble& rPointReadings = pScan->GetPointReadings();
06302 
06303       // compute transform to scan pose
06304       Transform transform(pScan->GetSensorPose());
06305 
06306       Pose2Vector localPoints;
06307       const_forEach(PointVectorDouble, &rPointReadings)
06308       {
06309         // do inverse transform to get points in local coordinates
06310         Pose2 vec = transform.InverseTransformPose(Pose2(*iter, 0.0));
06311         localPoints.push_back(vec);
06312       }
06313 
06315       // create lookup array for different angles
06316       kt_double angle = 0.0;
06317       kt_double startAngle = angleCenter - angleOffset;
06318       for (kt_int32u angleIndex = 0; angleIndex < nAngles; angleIndex++)
06319       {
06320         angle = startAngle + angleIndex * angleResolution;
06321         ComputeOffsets(angleIndex, angle, localPoints);
06322       }
06323       // assert(math::DoubleEqual(angle, angleCenter + angleOffset));
06324     }
06325 
06326   private:
06333     void ComputeOffsets(kt_int32u angleIndex, kt_double angle, const Pose2Vector& rLocalPoints)
06334     {
06335       m_ppLookupArray[angleIndex]->SetSize(static_cast<kt_int32u>(rLocalPoints.size()));
06336       m_Angles.at(angleIndex) = angle;
06337 
06338       // set up point array by computing relative offsets to points readings
06339       // when rotated by given angle
06340 
06341       const Vector2<kt_double>& rGridOffset = m_pGrid->GetCoordinateConverter()->GetOffset();
06342 
06343       kt_double cosine = cos(angle);
06344       kt_double sine = sin(angle);
06345 
06346       kt_int32u readingIndex = 0;
06347 
06348       kt_int32s* pAngleIndexPointer = m_ppLookupArray[angleIndex]->GetArrayPointer();
06349 
06350       const_forEach(Pose2Vector, &rLocalPoints)
06351       {
06352         const Vector2<kt_double>& rPosition = iter->GetPosition();
06353 
06354         // counterclockwise rotation and that rotation is about the origin (0, 0).
06355         Vector2<kt_double> offset;
06356         offset.SetX(cosine * rPosition.GetX() - sine * rPosition.GetY());
06357         offset.SetY(sine * rPosition.GetX() + cosine * rPosition.GetY());
06358 
06359         // have to compensate for the grid offset when getting the grid index
06360         Vector2<kt_int32s> gridPoint = m_pGrid->WorldToGrid(offset + rGridOffset);
06361 
06362         // use base GridIndex to ignore ROI
06363         kt_int32s lookupIndex = m_pGrid->Grid<T>::GridIndex(gridPoint, false);
06364 
06365         pAngleIndexPointer[readingIndex] = lookupIndex;
06366 
06367         readingIndex++;
06368       }
06369       assert(readingIndex == rLocalPoints.size());
06370     }
06371 
06376     void SetSize(kt_int32u size)
06377     {
06378       assert(size != 0);
06379 
06380       if (size > m_Capacity)
06381       {
06382         if (m_ppLookupArray != NULL)
06383         {
06384           DestroyArrays();
06385         }
06386 
06387         m_Capacity = size;
06388         m_ppLookupArray = new LookupArray*[m_Capacity];
06389         for (kt_int32u i = 0; i < m_Capacity; i++)
06390         {
06391           m_ppLookupArray[i] = new LookupArray();
06392         }
06393       }
06394 
06395       m_Size = size;
06396 
06397       m_Angles.resize(size);
06398     }
06399 
06403     void DestroyArrays()
06404     {
06405       for (kt_int32u i = 0; i < m_Capacity; i++)
06406       {
06407         delete m_ppLookupArray[i];
06408       }
06409 
06410       delete[] m_ppLookupArray;
06411       m_ppLookupArray = NULL;
06412     }
06413 
06414   private:
06415     Grid<T>* m_pGrid;
06416 
06417     kt_int32u m_Capacity;
06418     kt_int32u m_Size;
06419 
06420     LookupArray **m_ppLookupArray;
06421 
06422     // for sanity check
06423     std::vector<kt_double> m_Angles;
06424   };  // class GridIndexLookup
06425 
06429 
06430   inline Pose2::Pose2(const Pose3& rPose)
06431     : m_Position(rPose.GetPosition().GetX(), rPose.GetPosition().GetY())
06432   {
06433     kt_double t1, t2;
06434 
06435     // calculates heading from orientation
06436     rPose.GetOrientation().ToEulerAngles(m_Heading, t1, t2);
06437   }
06438 
06442 
06443   // @cond EXCLUDE
06444 
06445   template<typename T>
06446   inline void Object::SetParameter(const std::string& rName, T value)
06447   {
06448     AbstractParameter* pParameter = GetParameter(rName);
06449     if (pParameter != NULL)
06450     {
06451       std::stringstream stream;
06452       stream << value;
06453       pParameter->SetValueFromString(stream.str());
06454     }
06455     else
06456     {
06457       throw Exception("Parameter does not exist:  " + rName);
06458     }
06459   }
06460 
06461   template<>
06462   inline void Object::SetParameter(const std::string& rName, kt_bool value)
06463   {
06464     AbstractParameter* pParameter = GetParameter(rName);
06465     if (pParameter != NULL)
06466     {
06467       pParameter->SetValueFromString(value ? "true" : "false");
06468     }
06469     else
06470     {
06471       throw Exception("Parameter does not exist:  " + rName);
06472     }
06473   }
06474 
06475   // @endcond
06476 
06478 }  // namespace karto
06479 
06480 #endif  // OPEN_KARTO_KARTO_H


open_karto
Author(s):
autogenerated on Thu Aug 27 2015 14:14:06