00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #ifndef __KARTO_KARTO__
00019 #define __KARTO_KARTO__
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
00038 #ifdef USE_POCO
00039 #include <Poco/Mutex.h>
00040 #endif
00041
00042 #include "Math.h"
00043 #include "Macros.h"
00044
00045 #define KARTO_Object(name) \
00046 virtual const char* GetClassName() const { return #name; } \
00047 virtual kt_objecttype GetObjectType() const { return ObjectType_##name; }
00048
00049 typedef kt_int32u kt_objecttype;
00050
00051 const kt_objecttype ObjectType_None = 0x00000000;
00052 const kt_objecttype ObjectType_Sensor = 0x00001000;
00053 const kt_objecttype ObjectType_SensorData = 0x00002000;
00054 const kt_objecttype ObjectType_CustomData = 0x00004000;
00055 const kt_objecttype ObjectType_Misc = 0x10000000;
00056
00057 const kt_objecttype ObjectType_Drive = ObjectType_Sensor | 0x01;
00058 const kt_objecttype ObjectType_LaserRangeFinder = ObjectType_Sensor | 0x02;
00059
00060 const kt_objecttype ObjectType_DrivePose = ObjectType_SensorData | 0x01;
00061 const kt_objecttype ObjectType_LaserRangeScan = ObjectType_SensorData | 0x02;
00062 const kt_objecttype ObjectType_LocalizedRangeScan = ObjectType_SensorData | 0x03;
00063
00064 const kt_objecttype ObjectType_Parameters = ObjectType_Misc | 0x01;
00065 const kt_objecttype ObjectType_DatasetInfo = ObjectType_Misc | 0x02;
00066 const kt_objecttype ObjectType_Module = ObjectType_Misc | 0x03;
00067
00068 namespace karto
00069 {
00070
00074 class KARTO_EXPORT Exception
00075 {
00076 public:
00082 Exception(const std::string& rMessage = "Karto Exception", kt_int32s errorCode = 0)
00083 : m_Message(rMessage)
00084 , m_ErrorCode(errorCode)
00085 {
00086 }
00087
00091 Exception(const Exception& rException)
00092 : m_Message(rException.m_Message)
00093 , m_ErrorCode(rException.m_ErrorCode)
00094 {
00095 }
00096
00100 virtual ~Exception()
00101 {
00102 }
00103
00104 public:
00108 Exception& operator = (const Exception& rException)
00109 {
00110 m_Message = rException.m_Message;
00111 m_ErrorCode = rException.m_ErrorCode;
00112
00113 return *this;
00114 }
00115
00116 public:
00121 const std::string& GetErrorMessage() const
00122 {
00123 return m_Message;
00124 }
00125
00130 kt_int32s GetErrorCode()
00131 {
00132 return m_ErrorCode;
00133 }
00134
00135 public:
00141 friend KARTO_EXPORT std::ostream& operator << (std::ostream& rStream, Exception& rException);
00142
00143 private:
00144 std::string m_Message;
00145 kt_int32s m_ErrorCode;
00146 };
00147
00151
00152 class KARTO_EXPORT NonCopyable
00153 {
00154 private:
00155 NonCopyable(const NonCopyable&);
00156 const NonCopyable& operator=(const NonCopyable&);
00157
00158 protected:
00159 NonCopyable()
00160 {
00161 }
00162
00163 virtual ~NonCopyable()
00164 {
00165 }
00166 };
00167
00171
00172 template <class T>
00173 class Singleton
00174 {
00175 public:
00176 Singleton()
00177 : m_pPointer(NULL)
00178 {
00179 }
00180
00181 virtual ~Singleton()
00182 {
00183 delete m_pPointer;
00184 }
00185
00186 T* Get()
00187 {
00188 #ifdef USE_POCO
00189 Poco::FastMutex::ScopedLock lock(m_Mutex);
00190 #endif
00191 if (m_pPointer == NULL)
00192 {
00193 m_pPointer = new T;
00194 }
00195
00196 return m_pPointer;
00197 }
00198
00199 private:
00200 T* m_pPointer;
00201
00202 #ifdef USE_POCO
00203 Poco::FastMutex m_Mutex;
00204 #endif
00205
00206 private:
00207 Singleton(const Singleton&);
00208 const Singleton& operator=(const Singleton&);
00209 };
00210
00214
00215 class KARTO_EXPORT Functor
00216 {
00217 public:
00218 virtual void operator() (kt_int32u) {};
00219 };
00220
00224
00225 class AbstractParameter;
00226
00230 typedef std::vector<AbstractParameter*> ParameterVector;
00231
00232 class KARTO_EXPORT ParameterManager : public NonCopyable
00233 {
00234 public:
00238 ParameterManager()
00239 {
00240 }
00241
00245 virtual ~ParameterManager()
00246 {
00247 Clear();
00248 }
00249
00250 public:
00255 void Add(AbstractParameter* pParameter);
00256
00262 AbstractParameter* Get(const std::string& rName)
00263 {
00264 if (m_ParameterLookup.find(rName) != m_ParameterLookup.end())
00265 {
00266 return m_ParameterLookup[rName];
00267 }
00268
00269 std::cout << "Unknown parameter: " << rName << std::endl;
00270
00271 return NULL;
00272 }
00273
00277 void Clear();
00278
00283 inline const ParameterVector& GetParameterVector() const
00284 {
00285 return m_Parameters;
00286 }
00287
00288 public:
00294 AbstractParameter* operator() (const std::string& rName)
00295 {
00296 return Get(rName);
00297 }
00298
00299 private:
00300 ParameterManager(const ParameterManager&);
00301 const ParameterManager& operator=(const ParameterManager&);
00302
00303 private:
00304 ParameterVector m_Parameters;
00305 std::map<std::string, AbstractParameter*> m_ParameterLookup;
00306 };
00307
00311
00312
00313
00314
00315
00316
00317
00318 class Name
00319 {
00320 public:
00324 Name()
00325 {
00326 }
00327
00331 Name(const std::string& rName)
00332 {
00333 Parse(rName);
00334 }
00335
00339 Name(const Name& rOther)
00340 : m_Name(rOther.m_Name)
00341 , m_Scope(rOther.m_Scope)
00342 {
00343 }
00344
00348 virtual ~Name()
00349 {
00350 }
00351
00352 public:
00357 inline const std::string& GetName() const
00358 {
00359 return m_Name;
00360 }
00361
00366 inline void SetName(const std::string& rName)
00367 {
00368 std::string::size_type pos = rName.find_last_of('/');
00369 if(pos != 0 && pos != std::string::npos)
00370 {
00371 throw Exception("Name can't contain a scope!");
00372 }
00373
00374 m_Name = rName;
00375 }
00376
00381 inline const std::string& GetScope() const
00382 {
00383 return m_Scope;
00384 }
00385
00390 inline void SetScope(const std::string& rScope)
00391 {
00392 m_Scope = rScope;
00393 }
00394
00399 inline std::string ToString() const
00400 {
00401 if(m_Scope == "")
00402 {
00403 return m_Name;
00404 }
00405 else
00406 {
00407 std::string name;
00408 name.append("/");
00409 name.append(m_Scope);
00410 name.append("/");
00411 name.append(m_Name);
00412
00413 return name;
00414 }
00415 }
00416
00417 public:
00421 Name& operator = (const Name& rOther)
00422 {
00423 if (&rOther != this)
00424 {
00425 m_Name = rOther.m_Name;
00426 m_Scope = rOther.m_Scope;
00427 }
00428
00429 return *this;
00430 }
00431
00435 kt_bool operator == (const Name& rOther) const
00436 {
00437 return (m_Name == rOther.m_Name) && (m_Scope == rOther.m_Scope);
00438 }
00439
00443 kt_bool operator != (const Name& rOther) const
00444 {
00445 return !(*this == rOther);
00446 }
00447
00451 kt_bool operator < (const Name& rOther) const
00452 {
00453 return ToString() < rOther.ToString();
00454 }
00455
00461 friend inline std::ostream& operator << (std::ostream& rStream, const Name& rName)
00462 {
00463 rStream << rName.ToString();
00464 return rStream;
00465 }
00466
00467 private:
00472 void Parse(const std::string& rName)
00473 {
00474 std::string::size_type pos = rName.find_last_of('/');
00475
00476 if(pos == std::string::npos)
00477 {
00478 m_Name = rName;
00479 }
00480 else
00481 {
00482 m_Scope = rName.substr(0, pos);
00483 m_Name = rName.substr(pos+1, rName.size());
00484
00485
00486 if(m_Scope.size() > 0 && m_Scope[0] == '/')
00487 {
00488 m_Scope = m_Scope.substr(1, m_Scope.size());
00489 }
00490 }
00491 }
00492
00497 void Validate(const std::string& rName)
00498 {
00499 if (rName.empty())
00500 {
00501 return;
00502 }
00503
00504 char c = rName[0];
00505 if(IsValidFirst(c))
00506 {
00507 for (size_t i = 1; i < rName.size(); ++i)
00508 {
00509 c = rName[i];
00510 if (!IsValid(c))
00511 {
00512 throw Exception("Invalid character in name. Valid characters must be within the ranges A-Z, a-z, 0-9, '/', '_' and '-'.");
00513 }
00514 }
00515 }
00516 else
00517 {
00518 throw Exception("Invalid first character in name. Valid characters must be within the ranges A-Z, a-z, and '/'.");
00519 }
00520 }
00521
00527 inline kt_bool IsValidFirst(char c)
00528 {
00529 return (isalpha(c) || c == '/');
00530 }
00531
00537 inline kt_bool IsValid(char c)
00538 {
00539 return (isalnum(c) || c == '/' || c == '_' || c == '-');
00540 }
00541
00542 private:
00543 std::string m_Name;
00544 std::string m_Scope;
00545 };
00546
00550
00551 class KARTO_EXPORT Object : public NonCopyable
00552 {
00553 public:
00557 Object();
00558
00563 Object(const Name& rName);
00564
00568 virtual ~Object();
00569
00570 public:
00575 inline const Name& GetName() const
00576 {
00577 return m_Name;
00578 }
00579
00584 virtual const char* GetClassName() const = 0;
00585
00590 virtual kt_objecttype GetObjectType() const = 0;
00591
00596 virtual inline ParameterManager* GetParameterManager()
00597 {
00598 return m_pParameterManager;
00599 }
00600
00606 inline AbstractParameter* GetParameter(const std::string& rName) const
00607 {
00608 return m_pParameterManager->Get(rName);
00609 }
00610
00616 template<typename T>
00617 inline void SetParameter(const std::string& rName, T value);
00618
00623 inline const ParameterVector& GetParameters() const
00624 {
00625 return m_pParameterManager->GetParameterVector();
00626 }
00627
00628 private:
00629 Object(const Object&);
00630 const Object& operator=(const Object&);
00631
00632 private:
00633 Name m_Name;
00634 ParameterManager* m_pParameterManager;
00635 };
00636
00637 typedef std::vector<Object*> ObjectVector;
00638
00642
00648 inline kt_bool IsSensor(Object* pObject)
00649 {
00650 return (pObject->GetObjectType() & ObjectType_Sensor) == ObjectType_Sensor;
00651 }
00652
00658 inline kt_bool IsSensorData(Object* pObject)
00659 {
00660 return (pObject->GetObjectType() & ObjectType_SensorData) == ObjectType_SensorData;
00661 }
00662
00668 inline kt_bool IsLaserRangeFinder(Object* pObject)
00669 {
00670 return (pObject->GetObjectType() & ObjectType_LaserRangeFinder) == ObjectType_LaserRangeFinder;
00671 }
00672
00678 inline kt_bool IsLocalizedRangeScan(Object* pObject)
00679 {
00680 return (pObject->GetObjectType() & ObjectType_LocalizedRangeScan) == ObjectType_LocalizedRangeScan;
00681 }
00682
00688 inline kt_bool IsParameters(Object* pObject)
00689 {
00690 return (pObject->GetObjectType() & ObjectType_Parameters) == ObjectType_Parameters;
00691 }
00692
00698 inline kt_bool IsDatasetInfo(Object* pObject)
00699 {
00700 return (pObject->GetObjectType() & ObjectType_DatasetInfo) == ObjectType_DatasetInfo;
00701 }
00702
00706
00707 class KARTO_EXPORT Module : public Object
00708 {
00709 public:
00710 KARTO_Object(Module);
00711
00712 public:
00717 Module(const std::string& rName);
00718
00722 virtual ~Module();
00723
00724 public:
00725 virtual void Reset() = 0;
00726
00727 virtual kt_bool Process(karto::Object*)
00728 {
00729 return false;
00730 }
00731
00732 private:
00733 Module(const Module&);
00734 const Module& operator=(const Module&);
00735 };
00736
00740
00744 template<typename T>
00745 class Size2
00746 {
00747 public:
00751 Size2()
00752 : m_Width(0)
00753 , m_Height(0)
00754 {
00755 }
00756
00762 Size2(T width, T height)
00763 : m_Width(width)
00764 , m_Height(height)
00765 {
00766 }
00767
00772 Size2(const Size2& rOther)
00773 : m_Width(rOther.m_Width)
00774 , m_Height(rOther.m_Height)
00775 {
00776 }
00777
00778 public:
00783 inline const T GetWidth() const
00784 {
00785 return m_Width;
00786 }
00787
00792 inline void SetWidth(T width)
00793 {
00794 m_Width = width;
00795 }
00796
00801 inline const T GetHeight() const
00802 {
00803 return m_Height;
00804 }
00805
00810 inline void SetHeight(T height)
00811 {
00812 m_Height = height;
00813 }
00814
00818 inline Size2& operator = (const Size2& rOther)
00819 {
00820 m_Width = rOther.m_Width;
00821 m_Height = rOther.m_Height;
00822
00823 return(*this);
00824 }
00825
00829 inline kt_bool operator == (const Size2& rOther) const
00830 {
00831 return (m_Width == rOther.m_Width && m_Height == rOther.m_Height);
00832 }
00833
00837 inline kt_bool operator != (const Size2& rOther) const
00838 {
00839 return (m_Width != rOther.m_Width || m_Height != rOther.m_Height);
00840 }
00841
00847 friend inline std::ostream& operator << (std::ostream& rStream, const Size2& rSize)
00848 {
00849 rStream << "(" << rSize.m_Width << ", " << rSize.m_Height << ")";
00850 return rStream;
00851 }
00852
00853 private:
00854 T m_Width;
00855 T m_Height;
00856 };
00857
00861
00862 template<typename T>
00863 class Vector2
00864 {
00865 public:
00869 Vector2()
00870 {
00871 m_Values[0] = 0;
00872 m_Values[1] = 0;
00873 }
00874
00880 Vector2(T x, T y)
00881 {
00882 m_Values[0] = x;
00883 m_Values[1] = y;
00884 }
00885
00886 public:
00891 inline const T& GetX() const
00892 {
00893 return m_Values[0];
00894 }
00895
00900 inline void SetX(const T& x)
00901 {
00902 m_Values[0] = x;
00903 }
00904
00909 inline const T& GetY() const
00910 {
00911 return m_Values[1];
00912 }
00913
00918 inline void SetY(const T& y)
00919 {
00920 m_Values[1] = y;
00921 }
00922
00927 inline void MakeFloor(const Vector2& rOther)
00928 {
00929 if ( rOther.m_Values[0] < m_Values[0] ) m_Values[0] = rOther.m_Values[0];
00930 if ( rOther.m_Values[1] < m_Values[1] ) m_Values[1] = rOther.m_Values[1];
00931 }
00932
00937 inline void MakeCeil(const Vector2& rOther)
00938 {
00939 if ( rOther.m_Values[0] > m_Values[0] ) m_Values[0] = rOther.m_Values[0];
00940 if ( rOther.m_Values[1] > m_Values[1] ) m_Values[1] = rOther.m_Values[1];
00941 }
00942
00947 inline kt_double SquaredLength() const
00948 {
00949 return math::Square(m_Values[0]) + math::Square(m_Values[1]);
00950 }
00951
00956 inline kt_double Length() const
00957 {
00958 return sqrt(SquaredLength());
00959 }
00960
00965 inline kt_double SquaredDistance(const Vector2& rOther) const
00966 {
00967 return (*this - rOther).SquaredLength();
00968 }
00969
00975 inline kt_double Distance(const Vector2& rOther) const
00976 {
00977 return sqrt(SquaredDistance(rOther));
00978 }
00979
00980 public:
00984 inline void operator += (const Vector2& rOther)
00985 {
00986 m_Values[0] += rOther.m_Values[0];
00987 m_Values[1] += rOther.m_Values[1];
00988 }
00989
00993 inline void operator -= (const Vector2& rOther)
00994 {
00995 m_Values[0] -= rOther.m_Values[0];
00996 m_Values[1] -= rOther.m_Values[1];
00997 }
00998
01004 inline const Vector2 operator + (const Vector2& rOther) const
01005 {
01006 return Vector2(m_Values[0] + rOther.m_Values[0], m_Values[1] + rOther.m_Values[1]);
01007 }
01008
01014 inline const Vector2 operator - (const Vector2& rOther) const
01015 {
01016 return Vector2(m_Values[0] - rOther.m_Values[0], m_Values[1] - rOther.m_Values[1]);
01017 }
01018
01023 inline void operator /= (T scalar)
01024 {
01025 m_Values[0] /= scalar;
01026 m_Values[1] /= scalar;
01027 }
01028
01034 inline const Vector2 operator / (T scalar) const
01035 {
01036 return Vector2(m_Values[0] / scalar, m_Values[1] / scalar);
01037 }
01038
01044 inline kt_double operator * (const Vector2& rOther) const
01045 {
01046 return m_Values[0] * rOther.m_Values[0] + m_Values[1] * rOther.m_Values[1];
01047 }
01048
01053 inline const Vector2 operator * (T scalar) const
01054 {
01055 return Vector2(m_Values[0] * scalar, m_Values[1] * scalar);
01056 }
01057
01062 inline const Vector2 operator - (T scalar) const
01063 {
01064 return Vector2(m_Values[0] - scalar, m_Values[1] - scalar);
01065 }
01066
01071 inline void operator *= (T scalar)
01072 {
01073 m_Values[0] *= scalar;
01074 m_Values[1] *= scalar;
01075 }
01076
01081 inline kt_bool operator == (const Vector2& rOther) const
01082 {
01083 return (m_Values[0] == rOther.m_Values[0] && m_Values[1] == rOther.m_Values[1]);
01084 }
01085
01090 inline kt_bool operator != (const Vector2& rOther) const
01091 {
01092 return (m_Values[0] != rOther.m_Values[0] || m_Values[1] != rOther.m_Values[1]);
01093 }
01094
01100 inline kt_bool operator < (const Vector2& rOther) const
01101 {
01102 if (m_Values[0] < rOther.m_Values[0])
01103 return true;
01104 else if (m_Values[0] > rOther.m_Values[0])
01105 return false;
01106 else
01107 return (m_Values[1] < rOther.m_Values[1]);
01108 }
01109
01115 friend inline std::ostream& operator << (std::ostream& rStream, const Vector2& rVector)
01116 {
01117 rStream << rVector.GetX() << " " << rVector.GetY();
01118 return rStream;
01119 }
01120
01126 friend inline std::istream& operator >> (std::istream& rStream, const Vector2& )
01127 {
01128
01129 return rStream;
01130 }
01131
01132 private:
01133 T m_Values[2];
01134 };
01135
01139 typedef std::vector< Vector2<kt_double> > PointVectorDouble;
01140
01144
01145 template<typename T>
01146 class Vector3
01147 {
01148 public:
01152 Vector3()
01153 {
01154 m_Values[0] = 0;
01155 m_Values[1] = 0;
01156 m_Values[2] = 0;
01157 }
01158
01164 Vector3(T x, T y, T z)
01165 {
01166 m_Values[0] = x;
01167 m_Values[1] = y;
01168 m_Values[2] = z;
01169 }
01170
01175 Vector3(const Vector3& rOther)
01176 {
01177 m_Values[0] = rOther.m_Values[0];
01178 m_Values[1] = rOther.m_Values[1];
01179 m_Values[2] = rOther.m_Values[2];
01180 }
01181
01182 public:
01187 inline const T& GetX() const
01188 {
01189 return m_Values[0];
01190 }
01191
01196 inline void SetX(const T& x)
01197 {
01198 m_Values[0] = x;
01199 }
01200
01205 inline const T& GetY() const
01206 {
01207 return m_Values[1];
01208 }
01209
01214 inline void SetY(const T& y)
01215 {
01216 m_Values[1] = y;
01217 }
01218
01223 inline const T& GetZ() const
01224 {
01225 return m_Values[2];
01226 }
01227
01232 inline void SetZ(const T& z)
01233 {
01234 m_Values[2] = z;
01235 }
01236
01241 inline void MakeFloor(const Vector3& rOther)
01242 {
01243 if (rOther.m_Values[0] < m_Values[0]) m_Values[0] = rOther.m_Values[0];
01244 if (rOther.m_Values[1] < m_Values[1]) m_Values[1] = rOther.m_Values[1];
01245 if (rOther.m_Values[2] < m_Values[2]) m_Values[2] = rOther.m_Values[2];
01246 }
01247
01252 inline void MakeCeil(const Vector3& rOther)
01253 {
01254 if (rOther.m_Values[0] > m_Values[0]) m_Values[0] = rOther.m_Values[0];
01255 if (rOther.m_Values[1] > m_Values[1]) m_Values[1] = rOther.m_Values[1];
01256 if (rOther.m_Values[2] > m_Values[2]) m_Values[2] = rOther.m_Values[2];
01257 }
01258
01263 inline kt_double SquaredLength() const
01264 {
01265 return math::Square(m_Values[0]) + math::Square(m_Values[1]) + math::Square(m_Values[2]);
01266 }
01267
01272 inline kt_double Length() const
01273 {
01274 return sqrt(SquaredLength());
01275 }
01276
01281 inline std::string ToString() const
01282 {
01283 std::stringstream converter;
01284 converter.precision(std::numeric_limits<double>::digits10);
01285
01286 converter << GetX() << " " << GetY() << " " << GetZ();
01287
01288 return converter.str();
01289 }
01290
01291 public:
01295 inline Vector3& operator = (const Vector3& rOther)
01296 {
01297 m_Values[0] = rOther.m_Values[0];
01298 m_Values[1] = rOther.m_Values[1];
01299 m_Values[2] = rOther.m_Values[2];
01300
01301 return *this;
01302 }
01303
01309 inline const Vector3 operator + (const Vector3& rOther) const
01310 {
01311 return Vector3(m_Values[0] + rOther.m_Values[0], m_Values[1] + rOther.m_Values[1], m_Values[2] + rOther.m_Values[2]);
01312 }
01313
01319 inline const Vector3 operator + (kt_double scalar) const
01320 {
01321 return Vector3(m_Values[0] + scalar, m_Values[1] + scalar, m_Values[2] + scalar);
01322 }
01323
01329 inline const Vector3 operator - (const Vector3& rOther) const
01330 {
01331 return Vector3(m_Values[0] - rOther.m_Values[0], m_Values[1] - rOther.m_Values[1], m_Values[2] - rOther.m_Values[2]);
01332 }
01333
01339 inline const Vector3 operator - (kt_double scalar) const
01340 {
01341 return Vector3(m_Values[0] - scalar, m_Values[1] - scalar, m_Values[2] - scalar);
01342 }
01343
01348 inline const Vector3 operator * (T scalar) const
01349 {
01350 return Vector3(m_Values[0] * scalar, m_Values[1] * scalar, m_Values[2] * scalar);
01351 }
01352
01357 inline kt_bool operator == (const Vector3& rOther) const
01358 {
01359 return (m_Values[0] == rOther.m_Values[0] && m_Values[1] == rOther.m_Values[1] && m_Values[2] == rOther.m_Values[2]);
01360 }
01361
01366 inline kt_bool operator != (const Vector3& rOther) const
01367 {
01368 return (m_Values[0] != rOther.m_Values[0] || m_Values[1] != rOther.m_Values[1] || m_Values[2] != rOther.m_Values[2]);
01369 }
01370
01376 friend inline std::ostream& operator << (std::ostream& rStream, const Vector3& rVector)
01377 {
01378 rStream << rVector.ToString();
01379 return rStream;
01380 }
01381
01387 friend inline std::istream& operator >> (std::istream& rStream, const Vector3& )
01388 {
01389
01390 return rStream;
01391 }
01392
01393 private:
01394 T m_Values[3];
01395 };
01396
01400
01401 class Quaternion
01402 {
01403 public:
01407 inline Quaternion()
01408 {
01409 m_Values[0] = 0.0;
01410 m_Values[1] = 0.0;
01411 m_Values[2] = 0.0;
01412 m_Values[3] = 1.0;
01413 }
01414
01422 inline Quaternion(kt_double x, kt_double y, kt_double z, kt_double w)
01423 {
01424 m_Values[0] = x;
01425 m_Values[1] = y;
01426 m_Values[2] = z;
01427 m_Values[3] = w;
01428 }
01429
01433 inline Quaternion(const Quaternion& rQuaternion)
01434 {
01435 m_Values[0] = rQuaternion.m_Values[0];
01436 m_Values[1] = rQuaternion.m_Values[1];
01437 m_Values[2] = rQuaternion.m_Values[2];
01438 m_Values[3] = rQuaternion.m_Values[3];
01439 }
01440
01441 public:
01446 inline kt_double GetX() const
01447 {
01448 return m_Values[0];
01449 }
01450
01455 inline void SetX(kt_double x)
01456 {
01457 m_Values[0] = x;
01458 }
01459
01464 inline kt_double GetY() const
01465 {
01466 return m_Values[1];
01467 }
01468
01473 inline void SetY(kt_double y)
01474 {
01475 m_Values[1] = y;
01476 }
01477
01482 inline kt_double GetZ() const
01483 {
01484 return m_Values[2];
01485 }
01486
01491 inline void SetZ(kt_double z)
01492 {
01493 m_Values[2] = z;
01494 }
01495
01500 inline kt_double GetW() const
01501 {
01502 return m_Values[3];
01503 }
01504
01509 inline void SetW(kt_double w)
01510 {
01511 m_Values[3] = w;
01512 }
01513
01521 void ToEulerAngles(kt_double& rYaw, kt_double& rPitch, kt_double& rRoll) const
01522 {
01523 kt_double test = m_Values[0] * m_Values[1] + m_Values[2] * m_Values[3];
01524
01525 if (test > 0.499)
01526 {
01527
01528 rYaw = 2 * atan2(m_Values[0], m_Values[3]);;
01529 rPitch = KT_PI_2;
01530 rRoll = 0;
01531 }
01532 else if (test < -0.499)
01533 {
01534
01535 rYaw = -2 * atan2(m_Values[0], m_Values[3]);
01536 rPitch = -KT_PI_2;
01537 rRoll = 0;
01538 }
01539 else
01540 {
01541 kt_double sqx = m_Values[0] * m_Values[0];
01542 kt_double sqy = m_Values[1] * m_Values[1];
01543 kt_double sqz = m_Values[2] * m_Values[2];
01544
01545 rYaw = atan2(2 * m_Values[1] * m_Values[3] - 2 * m_Values[0] * m_Values[2], 1 - 2 * sqy - 2 * sqz);
01546 rPitch = asin(2 * test);
01547 rRoll = atan2(2 * m_Values[0] * m_Values[3] - 2 * m_Values[1] * m_Values[2], 1 - 2 * sqx - 2 * sqz);
01548 }
01549 }
01550
01558 void FromEulerAngles(kt_double yaw, kt_double pitch, kt_double roll)
01559 {
01560 kt_double angle;
01561
01562 angle = yaw * 0.5;
01563 kt_double cYaw = cos(angle);
01564 kt_double sYaw = sin(angle);
01565
01566 angle = pitch * 0.5;
01567 kt_double cPitch = cos(angle);
01568 kt_double sPitch = sin(angle);
01569
01570 angle = roll * 0.5;
01571 kt_double cRoll = cos(angle);
01572 kt_double sRoll = sin(angle);
01573
01574 m_Values[0] = sYaw * sPitch * cRoll + cYaw * cPitch * sRoll;
01575 m_Values[1] = sYaw * cPitch * cRoll + cYaw * sPitch * sRoll;
01576 m_Values[2] = cYaw * sPitch * cRoll - sYaw * cPitch * sRoll;
01577 m_Values[3] = cYaw * cPitch * cRoll - sYaw * sPitch * sRoll;
01578 }
01579
01584 inline Quaternion& operator = (const Quaternion& rQuaternion)
01585 {
01586 m_Values[0] = rQuaternion.m_Values[0];
01587 m_Values[1] = rQuaternion.m_Values[1];
01588 m_Values[2] = rQuaternion.m_Values[2];
01589 m_Values[3] = rQuaternion.m_Values[3];
01590
01591 return(*this);
01592 }
01593
01598 inline kt_bool operator == (const Quaternion& rOther) const
01599 {
01600 return (m_Values[0] == rOther.m_Values[0] && m_Values[1] == rOther.m_Values[1] && m_Values[2] == rOther.m_Values[2] && m_Values[3] == rOther.m_Values[3]);
01601 }
01602
01607 inline kt_bool operator != (const Quaternion& rOther) const
01608 {
01609 return (m_Values[0] != rOther.m_Values[0] || m_Values[1] != rOther.m_Values[1] || m_Values[2] != rOther.m_Values[2] || m_Values[3] != rOther.m_Values[3]);
01610 }
01611
01617 friend inline std::ostream& operator << (std::ostream& rStream, const Quaternion& rQuaternion)
01618 {
01619 rStream << rQuaternion.m_Values[0] << " " << rQuaternion.m_Values[1] << " " << rQuaternion.m_Values[2] << " " << rQuaternion.m_Values[3];
01620 return rStream;
01621 }
01622
01623 private:
01624 kt_double m_Values[4];
01625 };
01626
01630
01635 template<typename T>
01636 class Rectangle2
01637 {
01638 public:
01642 Rectangle2()
01643 {
01644 }
01645
01653 Rectangle2(T x, T y, T width, T height)
01654 : m_Position(x, y)
01655 , m_Size(width, height)
01656 {
01657 }
01658
01664 Rectangle2(const Vector2<T>& rPosition, const Size2<T>& rSize)
01665 : m_Position(rPosition)
01666 , m_Size(rSize)
01667 {
01668 }
01669
01673 Rectangle2(const Rectangle2& rOther)
01674 : m_Position(rOther.m_Position)
01675 , m_Size(rOther.m_Size)
01676 {
01677 }
01678
01679 public:
01684 inline T GetX() const
01685 {
01686 return m_Position.GetX();
01687 }
01688
01693 inline void SetX(T x)
01694 {
01695 m_Position.SetX(x);
01696 }
01697
01702 inline T GetY() const
01703 {
01704 return m_Position.GetY();
01705 }
01706
01711 inline void SetY(T y)
01712 {
01713 m_Position.SetY(y);
01714 }
01715
01720 inline T GetWidth() const
01721 {
01722 return m_Size.GetWidth();
01723 }
01724
01729 inline void SetWidth(T width)
01730 {
01731 m_Size.SetWidth(width);
01732 }
01733
01738 inline T GetHeight() const
01739 {
01740 return m_Size.GetHeight();
01741 }
01742
01747 inline void SetHeight(T height)
01748 {
01749 m_Size.SetHeight(height);
01750 }
01751
01756 inline const Vector2<T>& GetPosition() const
01757 {
01758 return m_Position;
01759 }
01760
01766 inline void SetPosition(const T& rX, const T& rY)
01767 {
01768 m_Position = Vector2<T>(rX, rY);
01769 }
01770
01775 inline void SetPosition(const Vector2<T>& rPosition)
01776 {
01777 m_Position = rPosition;
01778 }
01779
01784 inline const Size2<T>& GetSize() const
01785 {
01786 return m_Size;
01787 }
01788
01793 inline void SetSize(const Size2<T>& rSize)
01794 {
01795 m_Size = rSize;
01796 }
01797
01802 inline const Vector2<T> GetCenter() const
01803 {
01804 return Vector2<T>(m_Position.GetX() + m_Size.GetWidth() * 0.5, m_Position.GetY() + m_Size.GetHeight() * 0.5);
01805 }
01806
01807 public:
01811 Rectangle2& operator = (const Rectangle2& rOther)
01812 {
01813 m_Position = rOther.m_Position;
01814 m_Size = rOther.m_Size;
01815
01816 return *this;
01817 }
01818
01822 inline kt_bool operator == (const Rectangle2& rOther) const
01823 {
01824 return (m_Position == rOther.m_Position && m_Size == rOther.m_Size);
01825 }
01826
01830 inline kt_bool operator != (const Rectangle2& rOther) const
01831 {
01832 return (m_Position != rOther.m_Position || m_Size != rOther.m_Size);
01833 }
01834
01835 private:
01836 Vector2<T> m_Position;
01837 Size2<T> m_Size;
01838 };
01839
01843
01844 class Pose3;
01845
01849 class Pose2
01850 {
01851 public:
01855 Pose2()
01856 : m_Heading(0.0)
01857 {
01858 }
01859
01865 Pose2(const Vector2<kt_double>& rPosition, kt_double heading)
01866 : m_Position(rPosition)
01867 , m_Heading(heading)
01868 {
01869 }
01870
01877 Pose2(kt_double x, kt_double y, kt_double heading)
01878 : m_Position(x, y)
01879 , m_Heading(heading)
01880 {
01881 }
01882
01886 Pose2(const Pose3& rPose);
01887
01891 Pose2(const Pose2& rOther)
01892 : m_Position(rOther.m_Position)
01893 , m_Heading(rOther.m_Heading)
01894 {
01895 }
01896
01897 public:
01902 inline kt_double GetX() const
01903 {
01904 return m_Position.GetX();
01905 }
01906
01911 inline void SetX(kt_double x)
01912 {
01913 m_Position.SetX(x);
01914 }
01915
01920 inline kt_double GetY() const
01921 {
01922 return m_Position.GetY();
01923 }
01924
01929 inline void SetY(kt_double y)
01930 {
01931 m_Position.SetY(y);
01932 }
01933
01938 inline const Vector2<kt_double>& GetPosition() const
01939 {
01940 return m_Position;
01941 }
01942
01947 inline void SetPosition(const Vector2<kt_double>& rPosition)
01948 {
01949 m_Position = rPosition;
01950 }
01951
01956 inline kt_double GetHeading() const
01957 {
01958 return m_Heading;
01959 }
01960
01965 inline void SetHeading(kt_double heading)
01966 {
01967 m_Heading = heading;
01968 }
01969
01970 inline kt_double SquaredDistance(const Pose2& rOther) const
01971 {
01972 return m_Position.SquaredDistance(rOther.m_Position);
01973 }
01974
01975 public:
01979 inline Pose2& operator = (const Pose2& rOther)
01980 {
01981 m_Position = rOther.m_Position;
01982 m_Heading = rOther.m_Heading;
01983
01984 return *this;
01985 }
01986
01990 inline kt_bool operator == (const Pose2& rOther) const
01991 {
01992 return (m_Position == rOther.m_Position && m_Heading == rOther.m_Heading);
01993 }
01994
01998 inline kt_bool operator != (const Pose2& rOther) const
01999 {
02000 return (m_Position != rOther.m_Position || m_Heading != rOther.m_Heading);
02001 }
02002
02006 inline void operator += (const Pose2& rOther)
02007 {
02008 m_Position += rOther.m_Position;
02009 m_Heading = math::NormalizeAngle(m_Heading + rOther.m_Heading);
02010 }
02011
02017 inline Pose2 operator + (const Pose2& rOther) const
02018 {
02019 return Pose2(m_Position + rOther.m_Position, math::NormalizeAngle(m_Heading + rOther.m_Heading));
02020 }
02021
02027 inline Pose2 operator - (const Pose2& rOther) const
02028 {
02029 return Pose2(m_Position - rOther.m_Position, math::NormalizeAngle(m_Heading - rOther.m_Heading));
02030 }
02031
02037 friend inline std::istream& operator >> (std::istream& rStream, const Pose2& )
02038 {
02039
02040 return rStream;
02041 }
02042
02048 friend inline std::ostream& operator << (std::ostream& rStream, const Pose2& rPose)
02049 {
02050 rStream << rPose.m_Position.GetX() << " " << rPose.m_Position.GetY() << " " << rPose.m_Heading;
02051 return rStream;
02052 }
02053
02054 private:
02055 Vector2<kt_double> m_Position;
02056
02057 kt_double m_Heading;
02058 };
02059
02063 typedef std::vector< Pose2 > Pose2Vector;
02064
02068
02076 class Pose3
02077 {
02078 public:
02082 Pose3()
02083 {
02084 }
02085
02090 Pose3(const Vector3<kt_double>& rPosition)
02091 : m_Position(rPosition)
02092 {
02093 }
02094
02100 Pose3(const Vector3<kt_double>& rPosition, const karto::Quaternion& rOrientation)
02101 : m_Position(rPosition)
02102 , m_Orientation(rOrientation)
02103 {
02104 }
02105
02109 Pose3(const Pose3& rOther)
02110 : m_Position(rOther.m_Position)
02111 , m_Orientation(rOther.m_Orientation)
02112 {
02113 }
02114
02118 Pose3(const Pose2& rPose)
02119 {
02120 m_Position = Vector3<kt_double>(rPose.GetX(), rPose.GetY(), 0.0);
02121 m_Orientation.FromEulerAngles(rPose.GetHeading(), 0.0, 0.0);
02122 }
02123
02124 public:
02129 inline const Vector3<kt_double>& GetPosition() const
02130 {
02131 return m_Position;
02132 }
02133
02138 inline void SetPosition(const Vector3<kt_double>& rPosition)
02139 {
02140 m_Position = rPosition;
02141 }
02142
02147 inline const Quaternion& GetOrientation() const
02148 {
02149 return m_Orientation;
02150 }
02151
02156 inline void SetOrientation(const Quaternion& rOrientation)
02157 {
02158 m_Orientation = rOrientation;
02159 }
02160
02165 inline std::string ToString()
02166 {
02167 std::stringstream converter;
02168 converter.precision(std::numeric_limits<double>::digits10);
02169
02170 converter << GetPosition() << " " << GetOrientation();
02171
02172 return converter.str();
02173 }
02174
02175 public:
02179 inline Pose3& operator = (const Pose3& rOther)
02180 {
02181 m_Position = rOther.m_Position;
02182 m_Orientation = rOther.m_Orientation;
02183
02184 return *this;
02185 }
02186
02190 inline kt_bool operator == (const Pose3& rOther) const
02191 {
02192 return (m_Position == rOther.m_Position && m_Orientation == rOther.m_Orientation);
02193 }
02194
02198 inline kt_bool operator != (const Pose3& rOther) const
02199 {
02200 return (m_Position != rOther.m_Position || m_Orientation != rOther.m_Orientation);
02201 }
02202
02208 friend inline std::ostream& operator << (std::ostream& rStream, const Pose3& rPose)
02209 {
02210 rStream << rPose.GetPosition() << ", " << rPose.GetOrientation();
02211 return rStream;
02212 }
02213
02219 friend inline std::istream& operator >> (std::istream& rStream, const Pose3& )
02220 {
02221
02222 return rStream;
02223 }
02224
02225 private:
02226 Vector3<kt_double> m_Position;
02227 Quaternion m_Orientation;
02228 };
02229
02233
02237 class Matrix3
02238 {
02239 public:
02243 Matrix3()
02244 {
02245 Clear();
02246 }
02247
02251 inline Matrix3(const Matrix3& rOther)
02252 {
02253 memcpy(m_Matrix, rOther.m_Matrix, 9*sizeof(kt_double));
02254 }
02255
02256 public:
02260 void SetToIdentity()
02261 {
02262 memset(m_Matrix, 0, 9*sizeof(kt_double));
02263
02264 for (kt_int32s i = 0; i < 3; i++)
02265 {
02266 m_Matrix[i][i] = 1.0;
02267 }
02268 }
02269
02273 void Clear()
02274 {
02275 memset(m_Matrix, 0, 9*sizeof(kt_double));
02276 }
02277
02285 void FromAxisAngle(kt_double x, kt_double y, kt_double z, const kt_double radians)
02286 {
02287 kt_double cosRadians = cos(radians);
02288 kt_double sinRadians = sin(radians);
02289 kt_double oneMinusCos = 1.0 - cosRadians;
02290
02291 kt_double xx = x * x;
02292 kt_double yy = y * y;
02293 kt_double zz = z * z;
02294
02295 kt_double xyMCos = x * y * oneMinusCos;
02296 kt_double xzMCos = x * z * oneMinusCos;
02297 kt_double yzMCos = y * z * oneMinusCos;
02298
02299 kt_double xSin = x * sinRadians;
02300 kt_double ySin = y * sinRadians;
02301 kt_double zSin = z * sinRadians;
02302
02303 m_Matrix[0][0] = xx * oneMinusCos + cosRadians;
02304 m_Matrix[0][1] = xyMCos - zSin;
02305 m_Matrix[0][2] = xzMCos + ySin;
02306
02307 m_Matrix[1][0] = xyMCos + zSin;
02308 m_Matrix[1][1] = yy * oneMinusCos + cosRadians;
02309 m_Matrix[1][2] = yzMCos - xSin;
02310
02311 m_Matrix[2][0] = xzMCos - ySin;
02312 m_Matrix[2][1] = yzMCos + xSin;
02313 m_Matrix[2][2] = zz * oneMinusCos + cosRadians;
02314 }
02315
02320 Matrix3 Transpose() const
02321 {
02322 Matrix3 transpose;
02323
02324 for (kt_int32u row = 0; row < 3; row++)
02325 {
02326 for (kt_int32u col = 0; col < 3; col++)
02327 {
02328 transpose.m_Matrix[row][col] = m_Matrix[col][row];
02329 }
02330 }
02331
02332 return transpose;
02333 }
02334
02338 Matrix3 Inverse() const
02339 {
02340 Matrix3 kInverse = *this;
02341 kt_bool haveInverse = InverseFast(kInverse, 1e-14);
02342 if (haveInverse == false)
02343 {
02344 assert(false);
02345 }
02346 return kInverse;
02347 }
02348
02353 kt_bool InverseFast(Matrix3& rkInverse, kt_double fTolerance = KT_TOLERANCE) const
02354 {
02355
02356
02357 rkInverse.m_Matrix[0][0] = m_Matrix[1][1]*m_Matrix[2][2] - m_Matrix[1][2]*m_Matrix[2][1];
02358 rkInverse.m_Matrix[0][1] = m_Matrix[0][2]*m_Matrix[2][1] - m_Matrix[0][1]*m_Matrix[2][2];
02359 rkInverse.m_Matrix[0][2] = m_Matrix[0][1]*m_Matrix[1][2] - m_Matrix[0][2]*m_Matrix[1][1];
02360 rkInverse.m_Matrix[1][0] = m_Matrix[1][2]*m_Matrix[2][0] - m_Matrix[1][0]*m_Matrix[2][2];
02361 rkInverse.m_Matrix[1][1] = m_Matrix[0][0]*m_Matrix[2][2] - m_Matrix[0][2]*m_Matrix[2][0];
02362 rkInverse.m_Matrix[1][2] = m_Matrix[0][2]*m_Matrix[1][0] - m_Matrix[0][0]*m_Matrix[1][2];
02363 rkInverse.m_Matrix[2][0] = m_Matrix[1][0]*m_Matrix[2][1] - m_Matrix[1][1]*m_Matrix[2][0];
02364 rkInverse.m_Matrix[2][1] = m_Matrix[0][1]*m_Matrix[2][0] - m_Matrix[0][0]*m_Matrix[2][1];
02365 rkInverse.m_Matrix[2][2] = m_Matrix[0][0]*m_Matrix[1][1] - m_Matrix[0][1]*m_Matrix[1][0];
02366
02367 kt_double fDet = m_Matrix[0][0]*rkInverse.m_Matrix[0][0] + m_Matrix[0][1]*rkInverse.m_Matrix[1][0]+ m_Matrix[0][2]*rkInverse.m_Matrix[2][0];
02368
02369 if (fabs(fDet) <= fTolerance)
02370 {
02371 return false;
02372 }
02373
02374 kt_double fInvDet = 1.0/fDet;
02375 for (size_t row = 0; row < 3; row++)
02376 {
02377 for (size_t col = 0; col < 3; col++)
02378 {
02379 rkInverse.m_Matrix[row][col] *= fInvDet;
02380 }
02381 }
02382
02383 return true;
02384 }
02385
02390 inline std::string ToString() const
02391 {
02392 std::stringstream converter;
02393 converter.precision(std::numeric_limits<double>::digits10);
02394
02395 for (int row = 0; row < 3; row++)
02396 {
02397 for (int col = 0; col < 3; col++)
02398 {
02399 converter << m_Matrix[row][col] << " ";
02400 }
02401 }
02402
02403 return converter.str();
02404 }
02405
02406 public:
02410 inline Matrix3& operator = (const Matrix3& rOther)
02411 {
02412 memcpy(m_Matrix, rOther.m_Matrix, 9*sizeof(kt_double));
02413 return *this;
02414 }
02415
02422 inline kt_double& operator()(kt_int32u row, kt_int32u column)
02423 {
02424 return m_Matrix[row][column];
02425 }
02426
02433 inline kt_double operator()(kt_int32u row, kt_int32u column) const
02434 {
02435 return m_Matrix[row][column];
02436 }
02437
02443 Matrix3 operator * (const Matrix3& rOther) const
02444 {
02445 Matrix3 product;
02446
02447 for (size_t row = 0; row < 3; row++)
02448 {
02449 for (size_t col = 0; col < 3; col++)
02450 {
02451 product.m_Matrix[row][col] = m_Matrix[row][0]*rOther.m_Matrix[0][col] + m_Matrix[row][1]*rOther.m_Matrix[1][col] + m_Matrix[row][2]*rOther.m_Matrix[2][col];
02452 }
02453 }
02454
02455 return product;
02456 }
02457
02463 inline Pose2 operator * (const Pose2& rPose2) const
02464 {
02465 Pose2 pose2;
02466
02467 pose2.SetX(m_Matrix[0][0] * rPose2.GetX() + m_Matrix[0][1] * rPose2.GetY() + m_Matrix[0][2] * rPose2.GetHeading());
02468 pose2.SetY(m_Matrix[1][0] * rPose2.GetX() + m_Matrix[1][1] * rPose2.GetY() + m_Matrix[1][2] * rPose2.GetHeading());
02469 pose2.SetHeading(m_Matrix[2][0] * rPose2.GetX() + m_Matrix[2][1] * rPose2.GetY() + m_Matrix[2][2] * rPose2.GetHeading());
02470
02471 return pose2;
02472 }
02473
02478 inline void operator += (const Matrix3& rkMatrix)
02479 {
02480 for (kt_int32u row = 0; row < 3; row++)
02481 {
02482 for (kt_int32u col = 0; col < 3; col++)
02483 {
02484 m_Matrix[row][col] += rkMatrix.m_Matrix[row][col];
02485 }
02486 }
02487 }
02488
02494 friend inline std::ostream& operator << (std::ostream& rStream, const Matrix3& rMatrix)
02495 {
02496 rStream << rMatrix.ToString();
02497 return rStream;
02498 }
02499
02500 private:
02501 kt_double m_Matrix[3][3];
02502 };
02503
02507
02511 class Matrix
02512 {
02513 public:
02517 Matrix(kt_int32u rows, kt_int32u columns)
02518 : m_Rows(rows)
02519 , m_Columns(columns)
02520 , m_pData(NULL)
02521 {
02522 Allocate();
02523
02524 Clear();
02525 }
02526
02530 virtual ~Matrix()
02531 {
02532 delete [] m_pData;
02533 }
02534
02535 public:
02539 void Clear()
02540 {
02541 if (m_pData != NULL)
02542 {
02543 memset(m_pData, 0, sizeof(kt_double) * m_Rows * m_Columns);
02544 }
02545 }
02546
02551 inline kt_int32u GetRows() const
02552 {
02553 return m_Rows;
02554 }
02555
02560 inline kt_int32u GetColumns() const
02561 {
02562 return m_Columns;
02563 }
02564
02571 inline kt_double& operator()(kt_int32u row, kt_int32u column)
02572 {
02573 RangeCheck(row, column);
02574
02575 return m_pData[row + column * m_Rows];
02576 }
02577
02584 inline const kt_double& operator()(kt_int32u row, kt_int32u column) const
02585 {
02586 RangeCheck(row, column);
02587
02588 return m_pData[row + column * m_Rows];
02589 }
02590
02591 private:
02595 void Allocate()
02596 {
02597 try
02598 {
02599 if (m_pData != NULL)
02600 {
02601 delete[] m_pData;
02602 }
02603
02604 m_pData = new kt_double[m_Rows * m_Columns];
02605 }
02606 catch (std::bad_alloc exception)
02607 {
02608 throw Exception("Matrix allocation error");
02609 }
02610
02611 if (m_pData == NULL)
02612 {
02613 throw Exception("Matrix allocation error");
02614 }
02615 }
02616
02622 inline void RangeCheck(kt_int32u row, kt_int32u column) const
02623 {
02624 if (math::IsUpTo(row, m_Rows) == false)
02625 {
02626 throw Exception("Matrix - RangeCheck ERROR!!!!");
02627 }
02628
02629 if (math::IsUpTo(column, m_Columns) == false)
02630 {
02631 throw Exception("Matrix - RangeCheck ERROR!!!!");
02632 }
02633 }
02634
02635 private:
02636 kt_int32u m_Rows;
02637 kt_int32u m_Columns;
02638
02639 kt_double* m_pData;
02640 };
02641
02645
02649 class BoundingBox2
02650 {
02651 public:
02652
02653
02654
02655 BoundingBox2()
02656 : m_Minimum(999999999999999999.99999, 999999999999999999.99999)
02657 , m_Maximum(-999999999999999999.99999, -999999999999999999.99999)
02658 {
02659 }
02660
02661 public:
02665 inline const Vector2<kt_double>& GetMinimum() const
02666 {
02667 return m_Minimum;
02668 }
02669
02673 inline void SetMinimum(const Vector2<kt_double>& mMinimum)
02674 {
02675 m_Minimum = mMinimum;
02676 }
02677
02681 inline const Vector2<kt_double>& GetMaximum() const
02682 {
02683 return m_Maximum;
02684 }
02685
02689 inline void SetMaximum(const Vector2<kt_double>& rMaximum)
02690 {
02691 m_Maximum = rMaximum;
02692 }
02693
02697 inline Size2<kt_double> GetSize() const
02698 {
02699 Vector2<kt_double> size = m_Maximum - m_Minimum;
02700
02701 return Size2<kt_double>(size.GetX(), size.GetY());
02702 }
02703
02707 inline void Add(const Vector2<kt_double>& rPoint)
02708 {
02709 m_Minimum.MakeFloor(rPoint);
02710 m_Maximum.MakeCeil(rPoint);
02711 }
02712
02716 inline void Add(const BoundingBox2& rBoundingBox)
02717 {
02718 Add(rBoundingBox.GetMinimum());
02719 Add(rBoundingBox.GetMaximum());
02720 }
02721
02727 inline kt_bool IsInBounds(const Vector2<kt_double>& rPoint) const
02728 {
02729 return (math::InRange(rPoint.GetX(), m_Minimum.GetX(), m_Maximum.GetX()) &&
02730 math::InRange(rPoint.GetY(), m_Minimum.GetY(), m_Maximum.GetY()));
02731 }
02732
02733 private:
02734 Vector2<kt_double> m_Minimum;
02735 Vector2<kt_double> m_Maximum;
02736 };
02737
02741
02745 class Transform
02746 {
02747 public:
02752 Transform(const Pose2& rPose)
02753 {
02754 SetTransform(Pose2(), rPose);
02755 }
02756
02762 Transform(const Pose2& rPose1, const Pose2& rPose2)
02763 {
02764 SetTransform(rPose1, rPose2);
02765 }
02766
02767 public:
02773 inline Pose2 TransformPose(const Pose2& rSourcePose)
02774 {
02775 Pose2 newPosition = m_Transform + m_Rotation * rSourcePose;
02776 kt_double angle = math::NormalizeAngle(rSourcePose.GetHeading() + m_Transform.GetHeading());
02777
02778 return Pose2(newPosition.GetPosition(), angle);
02779 }
02780
02786 inline Pose2 InverseTransformPose(const Pose2& rSourcePose)
02787 {
02788 Pose2 newPosition = m_InverseRotation * (rSourcePose - m_Transform);
02789 kt_double angle = math::NormalizeAngle(rSourcePose.GetHeading() - m_Transform.GetHeading());
02790
02791
02792 return Pose2(newPosition.GetPosition(), angle);
02793 }
02794
02795 private:
02801 void SetTransform(const Pose2& rPose1, const Pose2& rPose2)
02802 {
02803 if (rPose1 == rPose2)
02804 {
02805 m_Rotation.SetToIdentity();
02806 m_InverseRotation.SetToIdentity();
02807 m_Transform = Pose2();
02808 return;
02809 }
02810
02811
02812 m_Rotation.FromAxisAngle(0, 0, 1, rPose2.GetHeading() - rPose1.GetHeading());
02813 m_InverseRotation.FromAxisAngle(0, 0, 1, rPose1.GetHeading() - rPose2.GetHeading());
02814
02815
02816 Pose2 newPosition;
02817 if (rPose1.GetX() != 0.0 || rPose1.GetY() != 0.0)
02818 {
02819 newPosition = rPose2 - m_Rotation * rPose1;
02820 }
02821 else
02822 {
02823 newPosition = rPose2;
02824 }
02825
02826 m_Transform = Pose2(newPosition.GetPosition(), rPose2.GetHeading() - rPose1.GetHeading());
02827 }
02828
02829 private:
02830
02831 Pose2 m_Transform;
02832
02833 Matrix3 m_Rotation;
02834 Matrix3 m_InverseRotation;
02835 };
02836
02840
02841 typedef enum
02842 {
02843 LaserRangeFinder_Custom = 0,
02844
02845 LaserRangeFinder_Sick_LMS100 = 1,
02846 LaserRangeFinder_Sick_LMS200 = 2,
02847 LaserRangeFinder_Sick_LMS291 = 3,
02848
02849 LaserRangeFinder_Hokuyo_UTM_30LX = 4,
02850 LaserRangeFinder_Hokuyo_URG_04LX = 5
02851 } LaserRangeFinderType;
02852
02856
02857 class AbstractParameter
02858 {
02859 public:
02864 AbstractParameter(const std::string& rName, ParameterManager* pParameterManger = NULL)
02865 : m_Name(rName)
02866 {
02867
02868 if (pParameterManger != NULL)
02869 {
02870 pParameterManger->Add(this);
02871 }
02872 }
02873
02879 AbstractParameter(const std::string& rName, const std::string& rDescription, ParameterManager* pParameterManger = NULL)
02880 : m_Name(rName)
02881 , m_Description(rDescription)
02882 {
02883
02884 if (pParameterManger != NULL)
02885 {
02886 pParameterManger->Add(this);
02887 }
02888 }
02889
02893 virtual ~AbstractParameter()
02894 {
02895 }
02896
02897 public:
02902 inline const std::string& GetName() const
02903 {
02904 return m_Name;
02905 }
02906
02911 inline const std::string& GetDescription() const
02912 {
02913 return m_Description;
02914 }
02915
02920 virtual const std::string GetValueAsString() const = 0;
02921
02926 virtual void SetValueFromString(const std::string& rStringValue) = 0;
02927
02932 virtual AbstractParameter* Clone() = 0;
02933
02934 public:
02940 friend std::ostream& operator << (std::ostream& rStream, const AbstractParameter& rParameter)
02941 {
02942 rStream.precision(6);
02943 rStream.flags(std::ios::fixed);
02944
02945 rStream << rParameter.GetName() << " = " << rParameter.GetValueAsString();
02946 return rStream;
02947 }
02948
02949 private:
02950 std::string m_Name;
02951 std::string m_Description;
02952 };
02953
02957
02958 template<typename T>
02959 class Parameter : public AbstractParameter
02960 {
02961 public:
02967 Parameter(const std::string& rName, T value, ParameterManager* pParameterManger = NULL)
02968 : AbstractParameter(rName, pParameterManger)
02969 , m_Value(value)
02970 {
02971 }
02972
02978 Parameter(const std::string& rName, const std::string& rDescription, T value, ParameterManager* pParameterManger = NULL)
02979 : AbstractParameter(rName, rDescription, pParameterManger)
02980 , m_Value(value)
02981 {
02982 }
02983
02987 virtual ~Parameter()
02988 {
02989 }
02990
02991 public:
02996 inline const T& GetValue() const
02997 {
02998 return m_Value;
02999 }
03000
03005 inline void SetValue(const T& rValue)
03006 {
03007 m_Value = rValue;
03008 }
03009
03014 virtual const std::string GetValueAsString() const
03015 {
03016 std::stringstream converter;
03017 converter << m_Value;
03018 return converter.str();
03019 }
03020
03025 virtual void SetValueFromString(const std::string& rStringValue)
03026 {
03027 std::stringstream converter;
03028 converter.str(rStringValue);
03029 converter >> m_Value;
03030 }
03031
03036 virtual Parameter* Clone()
03037 {
03038 return new Parameter(GetName(), GetDescription(), GetValue());
03039 }
03040
03041 public:
03045 Parameter& operator = (const Parameter& rOther)
03046 {
03047 m_Value = rOther.m_Value;
03048
03049 return *this;
03050 }
03051
03055 T operator = (T value)
03056 {
03057 m_Value = value;
03058
03059 return m_Value;
03060 }
03061
03062 protected:
03063 T m_Value;
03064 };
03065
03066 template<>
03067 inline void Parameter<kt_double>::SetValueFromString(const std::string& rStringValue)
03068 {
03069 int precision = std::numeric_limits<double>::digits10;
03070 std::stringstream converter;
03071 converter.precision(precision);
03072
03073 converter.str(rStringValue);
03074
03075 m_Value = 0.0;
03076 converter >> m_Value;
03077 }
03078
03079 template<>
03080 inline const std::string Parameter<kt_double>::GetValueAsString() const
03081 {
03082 std::stringstream converter;
03083 converter.precision(std::numeric_limits<double>::digits10);
03084 converter << m_Value;
03085 return converter.str();
03086 }
03087
03088 template<>
03089 inline void Parameter<kt_bool>::SetValueFromString(const std::string& rStringValue)
03090 {
03091 if (rStringValue == "true" || rStringValue == "TRUE")
03092 {
03093 m_Value = true;
03094 }
03095 else
03096 {
03097 m_Value = false;
03098 }
03099 }
03100
03101 template<>
03102 inline const std::string Parameter<kt_bool>::GetValueAsString() const
03103 {
03104 if (m_Value == true)
03105 {
03106 return "true";
03107 }
03108
03109 return "false";
03110 }
03111
03115
03119 class ParameterEnum : public Parameter<kt_int32s>
03120 {
03121 typedef std::map<std::string, kt_int32s> EnumMap;
03122
03123 public:
03129 ParameterEnum(const std::string& rName, kt_int32s value, ParameterManager* pParameterManger = NULL)
03130 : Parameter<kt_int32s>(rName, value, pParameterManger)
03131 {
03132 }
03133
03137 virtual ~ParameterEnum()
03138 {
03139 }
03140
03141 public:
03146 virtual Parameter<kt_int32s>* Clone()
03147 {
03148 ParameterEnum* pEnum = new ParameterEnum(GetName(), GetValue());
03149
03150 pEnum->m_EnumDefines = m_EnumDefines;
03151
03152 return pEnum;
03153 }
03154
03159 virtual void SetValueFromString(const std::string& rStringValue)
03160 {
03161 if (m_EnumDefines.find(rStringValue) != m_EnumDefines.end())
03162 {
03163 m_Value = m_EnumDefines[rStringValue];
03164 }
03165 else
03166 {
03167 std::string validValues;
03168
03169 const_forEach(EnumMap, &m_EnumDefines)
03170 {
03171 validValues += iter->first + ", ";
03172 }
03173
03174 throw Exception("Unable to set enum: " + rStringValue + ". Valid values are: " + validValues);
03175 }
03176 }
03177
03182 virtual const std::string GetValueAsString() const
03183 {
03184 const_forEach(EnumMap, &m_EnumDefines)
03185 {
03186 if (iter->second == m_Value)
03187 {
03188 return iter->first;
03189 }
03190 }
03191
03192 throw Exception("Unable to lookup enum");
03193 }
03194
03200 void DefineEnumValue(kt_int32s value, const std::string& rName)
03201 {
03202 if (m_EnumDefines.find(rName) == m_EnumDefines.end())
03203 {
03204 m_EnumDefines[rName] = value;
03205 }
03206 else
03207 {
03208 std::cerr << "Overriding enum value: " << m_EnumDefines[rName] << " with " << value << std::endl;
03209
03210 m_EnumDefines[rName] = value;
03211
03212 assert(false);
03213 }
03214 }
03215
03216 public:
03220 ParameterEnum& operator = (const ParameterEnum& rOther)
03221 {
03222 SetValue(rOther.GetValue());
03223
03224 return *this;
03225 }
03226
03230 kt_int32s operator = (kt_int32s value)
03231 {
03232 SetValue(value);
03233
03234 return m_Value;
03235 }
03236
03237 private:
03238 EnumMap m_EnumDefines;
03239 };
03240
03244
03245 class Parameters : public Object
03246 {
03247 public:
03248 KARTO_Object(Parameters)
03249
03250 public:
03255 Parameters(const std::string& rName)
03256 : Object(rName)
03257 {
03258 }
03259
03263 virtual ~Parameters()
03264 {
03265 }
03266
03267 private:
03268 Parameters(const Parameters&);
03269 const Parameters& operator=(const Parameters&);
03270 };
03271
03275
03276 class SensorData;
03277
03281 class KARTO_EXPORT Sensor : public Object
03282 {
03283 public:
03284 KARTO_Object(Sensor);
03285
03286 protected:
03291 Sensor(const Name& rName);
03292
03293 public:
03297 virtual ~Sensor();
03298
03299 public:
03304 inline const Pose2& GetOffsetPose() const
03305 {
03306 return m_pOffsetPose->GetValue();
03307 }
03308
03313 inline void SetOffsetPose(const Pose2& rPose)
03314 {
03315 m_pOffsetPose->SetValue(rPose);
03316 }
03317
03322 virtual kt_bool Validate() = 0;
03323
03329 virtual kt_bool Validate(SensorData* pSensorData) = 0;
03330
03331 private:
03335 Sensor(const Sensor&);
03336
03340 const Sensor& operator=(const Sensor&);
03341
03342 private:
03346 Parameter<Pose2>* m_pOffsetPose;
03347 };
03348
03349 typedef std::vector<Sensor*> SensorVector;
03350
03354
03355 typedef std::map<Name, Sensor*> SensorManagerMap;
03356
03360 class KARTO_EXPORT SensorManager
03361 {
03362 public:
03366 SensorManager()
03367 {
03368 }
03369
03373 virtual ~SensorManager()
03374 {
03375 }
03376
03377 public:
03381 static SensorManager* GetInstance();
03382
03383 public:
03390 void RegisterSensor(Sensor* pSensor, kt_bool override = false)
03391 {
03392 Validate(pSensor);
03393
03394 if ((m_Sensors.find(pSensor->GetName()) != m_Sensors.end()) && !override)
03395 {
03396 throw Exception("Cannot register sensor: already registered: " + pSensor->GetName().ToString());
03397 }
03398
03399
03400
03401 m_Sensors[pSensor->GetName()] = pSensor;
03402 }
03403
03408 void UnregisterSensor(Sensor* pSensor)
03409 {
03410 Validate(pSensor);
03411
03412 if(m_Sensors.find(pSensor->GetName()) != m_Sensors.end())
03413 {
03414
03415
03416 m_Sensors.erase(pSensor->GetName());
03417 }
03418 else
03419 {
03420 throw Exception("Cannot unregister sensor: not registered: " + pSensor->GetName().ToString());
03421 }
03422 }
03423
03429 Sensor* GetSensorByName(const Name& rName)
03430 {
03431 if(m_Sensors.find(rName) != m_Sensors.end())
03432 {
03433 return m_Sensors[rName];
03434 }
03435
03436 throw Exception("Sensor not registered: " + rName.ToString() + " (Did you add the sensor to the Dataset?)");
03437 }
03438
03444 template<class T>
03445 T* GetSensorByName(const Name& rName)
03446 {
03447 Sensor* pSensor = GetSensorByName(rName);
03448
03449 return dynamic_cast<T*>(pSensor);
03450 }
03451
03456 SensorVector GetAllSensors()
03457 {
03458 SensorVector sensors;
03459
03460 forEach(SensorManagerMap, &m_Sensors)
03461 {
03462 sensors.push_back(iter->second);
03463 }
03464
03465 return sensors;
03466 }
03467
03468 protected:
03473 static void Validate(Sensor* pSensor)
03474 {
03475 if (pSensor == NULL)
03476 {
03477 throw Exception("Invalid sensor: NULL");
03478 }
03479 else if (pSensor->GetName().ToString() == "")
03480 {
03481 throw Exception("Invalid sensor: nameless");
03482 }
03483 }
03484
03485 protected:
03486 SensorManagerMap m_Sensors;
03487 };
03488
03492
03499 class Drive : public Sensor
03500 {
03501 public:
03502 KARTO_Object(Drive)
03503
03504 public:
03508 Drive(const std::string& rName)
03509 : Sensor(rName)
03510 {
03511 }
03512
03516 virtual ~Drive()
03517 {
03518 }
03519
03520 public:
03521 virtual kt_bool Validate()
03522 {
03523 return true;
03524 }
03525
03526 virtual kt_bool Validate(SensorData* pSensorData)
03527 {
03528 if(pSensorData == NULL)
03529 {
03530 return false;
03531 }
03532
03533 return true;
03534 }
03535
03536 private:
03537 Drive(const Drive&);
03538 const Drive& operator=(const Drive&);
03539 };
03540
03544
03545 class LocalizedRangeScan;
03546 class CoordinateConverter;
03547
03560 class KARTO_EXPORT LaserRangeFinder : public Sensor
03561 {
03562 public:
03563 KARTO_Object(LaserRangeFinder)
03564
03565 public:
03569 virtual ~LaserRangeFinder()
03570 {
03571 }
03572
03573 public:
03578 inline kt_double GetMinimumRange() const
03579 {
03580 return m_pMinimumRange->GetValue();
03581 }
03582
03587 inline void SetMinimumRange(kt_double minimumRange)
03588 {
03589 m_pMinimumRange->SetValue(minimumRange);
03590
03591 SetRangeThreshold(GetRangeThreshold());
03592 }
03593
03598 inline kt_double GetMaximumRange() const
03599 {
03600 return m_pMaximumRange->GetValue();
03601 }
03602
03607 inline void SetMaximumRange(kt_double maximumRange)
03608 {
03609 m_pMaximumRange->SetValue(maximumRange);
03610
03611 SetRangeThreshold(GetRangeThreshold());
03612 }
03613
03618 inline kt_double GetRangeThreshold() const
03619 {
03620 return m_pRangeThreshold->GetValue();
03621 }
03622
03627 inline void SetRangeThreshold(kt_double rangeThreshold)
03628 {
03629
03630 m_pRangeThreshold->SetValue(math::Clip(rangeThreshold, GetMinimumRange(), GetMaximumRange()));
03631
03632 if (math::DoubleEqual(GetRangeThreshold(), rangeThreshold) == false)
03633 {
03634
03635 }
03636 }
03637
03642 inline kt_double GetMinimumAngle() const
03643 {
03644 return m_pMinimumAngle->GetValue();
03645 }
03646
03651 inline void SetMinimumAngle(kt_double minimumAngle)
03652 {
03653 m_pMinimumAngle->SetValue(minimumAngle);
03654
03655 Update();
03656 }
03657
03662 inline kt_double GetMaximumAngle() const
03663 {
03664 return m_pMaximumAngle->GetValue();
03665 }
03666
03671 inline void SetMaximumAngle(kt_double maximumAngle)
03672 {
03673 m_pMaximumAngle->SetValue(maximumAngle);
03674
03675 Update();
03676 }
03677
03682 inline kt_double GetAngularResolution() const
03683 {
03684 return m_pAngularResolution->GetValue();
03685 }
03686
03691 inline void SetAngularResolution(kt_double angularResolution)
03692 {
03693 if (m_pType->GetValue() == LaserRangeFinder_Custom)
03694 {
03695 m_pAngularResolution->SetValue(angularResolution);
03696 }
03697 else if (m_pType->GetValue() == LaserRangeFinder_Sick_LMS100)
03698 {
03699 if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.25)))
03700 {
03701 m_pAngularResolution->SetValue(math::DegreesToRadians(0.25));
03702 }
03703 else if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.50)))
03704 {
03705 m_pAngularResolution->SetValue(math::DegreesToRadians(0.50));
03706 }
03707 else
03708 {
03709 std::stringstream stream;
03710 stream << "Invalid resolution for Sick LMS100: ";
03711 stream << angularResolution;
03712 throw karto::Exception(stream.str());
03713 }
03714 }
03715 else if (m_pType->GetValue() == LaserRangeFinder_Sick_LMS200 || m_pType->GetValue() == LaserRangeFinder_Sick_LMS291)
03716 {
03717 if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.25)))
03718 {
03719 m_pAngularResolution->SetValue(math::DegreesToRadians(0.25));
03720 }
03721 else if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.50)))
03722 {
03723 m_pAngularResolution->SetValue(math::DegreesToRadians(0.50));
03724 }
03725 else if (math::DoubleEqual(angularResolution, math::DegreesToRadians(1.00)))
03726 {
03727 m_pAngularResolution->SetValue(math::DegreesToRadians(1.00));
03728 }
03729 else
03730 {
03731 std::stringstream stream;
03732 stream << "Invalid resolution for Sick LMS291: ";
03733 stream << angularResolution;
03734 throw karto::Exception(stream.str());
03735 }
03736 }
03737 else
03738 {
03739 throw karto::Exception("Can't set angular resolution, please create a LaserRangeFinder of type Custom");
03740 return;
03741 }
03742
03743 Update();
03744 }
03745
03746 inline kt_int32s GetType()
03747 {
03748 return m_pType->GetValue();
03749 }
03750
03755 inline kt_int32u GetNumberOfRangeReadings() const
03756 {
03757 return m_NumberOfRangeReadings;
03758 }
03759
03760 virtual kt_bool Validate()
03761 {
03762 Update();
03763
03764 if (math::InRange(GetRangeThreshold(), GetMinimumRange(), GetMaximumRange()) == false)
03765 {
03766
03767 return false;
03768 }
03769
03770 return true;
03771 }
03772
03773 virtual kt_bool Validate(SensorData* pSensorData);
03774
03779 const PointVectorDouble GetPointReadings(LocalizedRangeScan* pLocalizedRangeScan, CoordinateConverter* pCoordinateConverter, kt_bool ignoreThresholdPoints = true, kt_bool flipY = false) const;
03780
03781 public:
03788 static LaserRangeFinder* CreateLaserRangeFinder(LaserRangeFinderType type, const Name& rName)
03789 {
03790 LaserRangeFinder* pLrf = NULL;
03791
03792 switch(type)
03793 {
03794
03795
03796 case LaserRangeFinder_Sick_LMS100:
03797 {
03798 pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Sick LMS 100"));
03799
03800
03801 pLrf->m_pMinimumRange->SetValue(0.0);
03802 pLrf->m_pMaximumRange->SetValue(20.0);
03803
03804
03805 pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-135));
03806 pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(135));
03807
03808
03809 pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.25));
03810
03811 pLrf->m_NumberOfRangeReadings = 1081;
03812 }
03813 break;
03814
03815
03816
03817 case LaserRangeFinder_Sick_LMS200:
03818 {
03819 pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Sick LMS 200"));
03820
03821
03822 pLrf->m_pMinimumRange->SetValue(0.0);
03823 pLrf->m_pMaximumRange->SetValue(80.0);
03824
03825
03826 pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-90));
03827 pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(90));
03828
03829
03830 pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.5));
03831
03832 pLrf->m_NumberOfRangeReadings = 361;
03833 }
03834 break;
03835
03836
03837
03838 case LaserRangeFinder_Sick_LMS291:
03839 {
03840 pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Sick LMS 291"));
03841
03842
03843 pLrf->m_pMinimumRange->SetValue(0.0);
03844 pLrf->m_pMaximumRange->SetValue(80.0);
03845
03846
03847 pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-90));
03848 pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(90));
03849
03850
03851 pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.5));
03852
03853 pLrf->m_NumberOfRangeReadings = 361;
03854 }
03855 break;
03856
03857
03858
03859 case LaserRangeFinder_Hokuyo_UTM_30LX:
03860 {
03861 pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Hokuyo UTM-30LX"));
03862
03863
03864 pLrf->m_pMinimumRange->SetValue(0.1);
03865 pLrf->m_pMaximumRange->SetValue(30.0);
03866
03867
03868 pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-135));
03869 pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(135));
03870
03871
03872 pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.25));
03873
03874 pLrf->m_NumberOfRangeReadings = 1081;
03875 }
03876 break;
03877
03878
03879
03880 case LaserRangeFinder_Hokuyo_URG_04LX:
03881 {
03882 pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Hokuyo URG-04LX"));
03883
03884
03885 pLrf->m_pMinimumRange->SetValue(0.02);
03886 pLrf->m_pMaximumRange->SetValue(4.0);
03887
03888
03889 pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-120));
03890 pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(120));
03891
03892
03893 pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.352));
03894
03895 pLrf->m_NumberOfRangeReadings = 751;
03896 }
03897 break;
03898
03899 case LaserRangeFinder_Custom:
03900 {
03901 pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("User-Defined LaserRangeFinder"));
03902
03903
03904 pLrf->m_pMinimumRange->SetValue(0.0);
03905 pLrf->m_pMaximumRange->SetValue(80.0);
03906
03907
03908 pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-90));
03909 pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(90));
03910
03911
03912 pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(1.0));
03913
03914 pLrf->m_NumberOfRangeReadings = 181;
03915 }
03916 break;
03917 }
03918
03919 if (pLrf != NULL)
03920 {
03921 pLrf->m_pType->SetValue(type);
03922
03923 Pose2 defaultOffset;
03924 pLrf->SetOffsetPose(defaultOffset);
03925 }
03926
03927 return pLrf;
03928 }
03929
03930 private:
03934 LaserRangeFinder(const Name& rName)
03935 : Sensor(rName)
03936 , m_NumberOfRangeReadings(0)
03937 {
03938 m_pMinimumRange = new Parameter<kt_double>("MinimumRange", 0.0, GetParameterManager());
03939 m_pMaximumRange = new Parameter<kt_double>("MaximumRange", 80.0, GetParameterManager());
03940
03941 m_pMinimumAngle = new Parameter<kt_double>("MinimumAngle", -KT_PI_2, GetParameterManager());
03942 m_pMaximumAngle = new Parameter<kt_double>("MaximumAngle", KT_PI_2, GetParameterManager());
03943
03944 m_pAngularResolution = new Parameter<kt_double>("AngularResolution", math::DegreesToRadians(1), GetParameterManager());
03945
03946 m_pRangeThreshold = new Parameter<kt_double>("RangeThreshold", 12.0, GetParameterManager());
03947
03948 m_pType = new ParameterEnum("Type", LaserRangeFinder_Custom, GetParameterManager());
03949 m_pType->DefineEnumValue(LaserRangeFinder_Custom, "Custom");
03950 m_pType->DefineEnumValue(LaserRangeFinder_Sick_LMS100, "Sick_LMS100");
03951 m_pType->DefineEnumValue(LaserRangeFinder_Sick_LMS200, "Sick_LMS200");
03952 m_pType->DefineEnumValue(LaserRangeFinder_Sick_LMS291, "Sick_LMS291");
03953 m_pType->DefineEnumValue(LaserRangeFinder_Hokuyo_UTM_30LX, "Hokuyo_UTM_30LX");
03954 m_pType->DefineEnumValue(LaserRangeFinder_Hokuyo_URG_04LX, "Hokuyo_URG_04LX");
03955 }
03956
03960 void Update()
03961 {
03962 m_NumberOfRangeReadings = static_cast<kt_int32u>(math::Round((GetMaximumAngle() - GetMinimumAngle()) / GetAngularResolution()) + 1);
03963 }
03964
03965 private:
03966 LaserRangeFinder(const LaserRangeFinder&);
03967 const LaserRangeFinder& operator=(const LaserRangeFinder&);
03968
03969 private:
03970
03971 Parameter<kt_double>* m_pMinimumAngle;
03972 Parameter<kt_double>* m_pMaximumAngle;
03973
03974 Parameter<kt_double>* m_pAngularResolution;
03975
03976 Parameter<kt_double>* m_pMinimumRange;
03977 Parameter<kt_double>* m_pMaximumRange;
03978
03979 Parameter<kt_double>* m_pRangeThreshold;
03980
03981 ParameterEnum* m_pType;
03982
03983 kt_int32u m_NumberOfRangeReadings;
03984
03985
03986 };
03987
03991
03995 typedef enum
03996 {
03997 GridStates_Unknown = 0,
03998 GridStates_Occupied = 100,
03999 GridStates_Free = 255
04000 } GridStates;
04001
04005
04011 class CoordinateConverter
04012 {
04013 public:
04017 CoordinateConverter()
04018 : m_Scale(20.0)
04019 {
04020 }
04021
04022 public:
04028 inline kt_double Transform(kt_double value)
04029 {
04030 return value * m_Scale;
04031 }
04032
04038 inline Vector2<kt_int32s> WorldToGrid(const Vector2<kt_double>& rWorld, kt_bool flipY = false) const
04039 {
04040 kt_double gridX = (rWorld.GetX() - m_Offset.GetX()) * m_Scale;
04041 kt_double gridY = 0.0;
04042
04043 if (flipY == false)
04044 {
04045 gridY = (rWorld.GetY() - m_Offset.GetY()) * m_Scale;
04046 }
04047 else
04048 {
04049 gridY = (m_Size.GetHeight() / m_Scale - rWorld.GetY() + m_Offset.GetY()) * m_Scale;
04050 }
04051
04052 return Vector2<kt_int32s>(static_cast<kt_int32s>(math::Round(gridX)), static_cast<kt_int32s>(math::Round(gridY)));
04053 }
04054
04060 inline Vector2<kt_double> GridToWorld(const Vector2<kt_int32s>& rGrid, kt_bool flipY = false) const
04061 {
04062 kt_double worldX = m_Offset.GetX() + rGrid.GetX() / m_Scale;
04063 kt_double worldY = 0.0;
04064
04065 if (flipY == false)
04066 {
04067 worldY = m_Offset.GetY() + rGrid.GetY() / m_Scale;
04068 }
04069 else
04070 {
04071 worldY = m_Offset.GetY() + (m_Size.GetHeight() - rGrid.GetY()) / m_Scale;
04072 }
04073
04074 return Vector2<kt_double>(worldX, worldY);
04075 }
04076
04081 inline kt_double GetScale() const
04082 {
04083 return m_Scale;
04084 }
04085
04090 inline void SetScale(kt_double scale)
04091 {
04092 m_Scale = scale;
04093 }
04094
04099 inline const Vector2<kt_double>& GetOffset() const
04100 {
04101 return m_Offset;
04102 }
04103
04108 inline void SetOffset(const Vector2<kt_double>& rOffset)
04109 {
04110 m_Offset = rOffset;
04111 }
04112
04117 inline void SetSize(const Size2<kt_int32s>& rSize)
04118 {
04119 m_Size = rSize;
04120 }
04121
04126 inline const Size2<kt_int32s>& GetSize() const
04127 {
04128 return m_Size;
04129 }
04130
04135 inline kt_double GetResolution() const
04136 {
04137 return 1.0 / m_Scale;
04138 }
04139
04144 inline void SetResolution(kt_double resolution)
04145 {
04146 m_Scale = 1.0 / resolution;
04147 }
04148
04153 inline BoundingBox2 GetBoundingBox() const
04154 {
04155 BoundingBox2 box;
04156
04157 kt_double minX = GetOffset().GetX();
04158 kt_double minY = GetOffset().GetY();
04159 kt_double maxX = minX + GetSize().GetWidth() * GetResolution();
04160 kt_double maxY = minY + GetSize().GetHeight() * GetResolution();
04161
04162 box.SetMinimum(GetOffset());
04163 box.SetMaximum(Vector2<kt_double>(maxX, maxY));
04164 return box;
04165 }
04166
04167 private:
04168 Size2<kt_int32s> m_Size;
04169 kt_double m_Scale;
04170
04171 Vector2<kt_double> m_Offset;
04172 };
04173
04177
04181 template<typename T>
04182 class Grid
04183 {
04184 public:
04192 static Grid* CreateGrid(kt_int32s width, kt_int32s height, kt_double resolution)
04193 {
04194 Grid* pGrid = new Grid(width, height);
04195
04196 pGrid->GetCoordinateConverter()->SetScale(1.0 / resolution);
04197
04198 return pGrid;
04199 }
04200
04204 virtual ~Grid()
04205 {
04206 delete [] m_pData;
04207 delete m_pCoordinateConverter;
04208 }
04209
04210 public:
04214 void Clear()
04215 {
04216 memset(m_pData, 0, GetDataSize() * sizeof(T));
04217 }
04218
04223 Grid* Clone()
04224 {
04225 Grid* pGrid = CreateGrid(GetWidth(), GetHeight(), GetResolution());
04226 pGrid->GetCoordinateConverter()->SetOffset(GetCoordinateConverter()->GetOffset());
04227
04228 memcpy(pGrid->GetDataPointer(), GetDataPointer(), GetDataSize());
04229
04230 return pGrid;
04231 }
04232
04238 virtual void Resize(kt_int32s width, kt_int32s height)
04239 {
04240 m_Width = width;
04241 m_Height = height;
04242 m_WidthStep = math::AlignValue<kt_int32s>(width, 8);
04243
04244 if (m_pData != NULL)
04245 {
04246 delete[] m_pData;
04247 m_pData = NULL;
04248 }
04249
04250 try
04251 {
04252 m_pData = new T[GetDataSize()];
04253
04254 if (m_pCoordinateConverter == NULL)
04255 {
04256 m_pCoordinateConverter = new CoordinateConverter();
04257 }
04258
04259 m_pCoordinateConverter->SetSize(Size2<kt_int32s>(width, height));
04260 }
04261 catch(...)
04262 {
04263 m_pData = NULL;
04264
04265 m_Width = 0;
04266 m_Height = 0;
04267 m_WidthStep = 0;
04268 }
04269
04270 Clear();
04271 }
04272
04278 inline kt_bool IsValidGridIndex(const Vector2<kt_int32s>& rGrid) const
04279 {
04280 return (math::IsUpTo(rGrid.GetX(), m_Width) && math::IsUpTo(rGrid.GetY(), m_Height));
04281 }
04282
04289 virtual kt_int32s GridIndex(const Vector2<kt_int32s>& rGrid, kt_bool boundaryCheck = true) const
04290 {
04291 if (boundaryCheck == true)
04292 {
04293 if (IsValidGridIndex(rGrid) == false)
04294 {
04295 std::stringstream error;
04296 error << "Index " << rGrid << " out of range. Index must be between [0; " << m_Width << ") and [0; " << m_Height << ")";
04297 throw Exception(error.str());
04298 }
04299 }
04300
04301 kt_int32s index = rGrid.GetX() + (rGrid.GetY() * m_WidthStep);
04302
04303 if (boundaryCheck == true)
04304 {
04305 assert(math::IsUpTo(index, GetDataSize()));
04306 }
04307
04308 return index;
04309 }
04310
04316 Vector2<kt_int32s> IndexToGrid(kt_int32s index) const
04317 {
04318 Vector2<kt_int32s> grid;
04319
04320 grid.SetY(index / m_WidthStep);
04321 grid.SetX(index - grid.GetY() * m_WidthStep);
04322
04323 return grid;
04324 }
04325
04331 inline Vector2<kt_int32s> WorldToGrid(const Vector2<kt_double>& rWorld, kt_bool flipY = false) const
04332 {
04333 return GetCoordinateConverter()->WorldToGrid(rWorld, flipY);
04334 }
04335
04341 inline Vector2<kt_double> GridToWorld(const Vector2<kt_int32s>& rGrid, kt_bool flipY = false) const
04342 {
04343 return GetCoordinateConverter()->GridToWorld(rGrid, flipY);
04344 }
04345
04351 T* GetDataPointer(const Vector2<kt_int32s>& rGrid)
04352 {
04353 kt_int32s index = GridIndex(rGrid, true);
04354 return m_pData + index;
04355 }
04356
04362 T* GetDataPointer(const Vector2<kt_int32s>& rGrid) const
04363 {
04364 kt_int32s index = GridIndex(rGrid, true);
04365 return m_pData + index;
04366 }
04367
04372 inline kt_int32s GetWidth() const
04373 {
04374 return m_Width;
04375 };
04376
04381 inline kt_int32s GetHeight() const
04382 {
04383 return m_Height;
04384 };
04385
04386 inline const Size2<kt_int32s> GetSize() const
04387 {
04388 return Size2<kt_int32s>(m_Width, m_Height);
04389 }
04390
04395 inline kt_int32s GetWidthStep() const
04396 {
04397 return m_WidthStep;
04398 }
04399
04404 inline T* GetDataPointer()
04405 {
04406 return m_pData;
04407 }
04408
04413 inline T* GetDataPointer() const
04414 {
04415 return m_pData;
04416 }
04417
04422 inline kt_int32s GetDataSize() const
04423 {
04424 return m_WidthStep * m_Height;
04425 }
04426
04432 inline T GetValue(const Vector2<kt_int32s>& rGrid) const
04433 {
04434 kt_int32s index = GridIndex(rGrid);
04435 return m_pData[index];
04436 }
04437
04442 inline CoordinateConverter* GetCoordinateConverter() const
04443 {
04444 return m_pCoordinateConverter;
04445 }
04446
04451 inline kt_double GetResolution() const
04452 {
04453 return GetCoordinateConverter()->GetResolution();
04454 }
04455
04460 inline BoundingBox2 GetBoundingBox() const
04461 {
04462 return GetCoordinateConverter()->GetBoundingBox();
04463 }
04464
04474 void TraceLine(kt_int32s x0, kt_int32s y0, kt_int32s x1, kt_int32s y1, Functor* f = NULL)
04475 {
04476 kt_bool steep = abs(y1 - y0) > abs(x1 - x0);
04477 if (steep)
04478 {
04479 std::swap(x0, y0);
04480 std::swap(x1, y1);
04481 }
04482 if (x0 > x1)
04483 {
04484 std::swap(x0, x1);
04485 std::swap(y0, y1);
04486 }
04487
04488 kt_int32s deltaX = x1 - x0;
04489 kt_int32s deltaY = abs(y1 - y0);
04490 kt_int32s error = 0;
04491 kt_int32s ystep;
04492 kt_int32s y = y0;
04493
04494 if (y0 < y1)
04495 {
04496 ystep = 1;
04497 }
04498 else
04499 {
04500 ystep = -1;
04501 }
04502
04503 kt_int32s pointX;
04504 kt_int32s pointY;
04505 for (kt_int32s x = x0; x <= x1; x++)
04506 {
04507 if (steep)
04508 {
04509 pointX = y;
04510 pointY = x;
04511 }
04512 else
04513 {
04514 pointX = x;
04515 pointY = y;
04516 }
04517
04518 error += deltaY;
04519
04520 if (2 * error >= deltaX)
04521 {
04522 y += ystep;
04523 error -= deltaX;
04524 }
04525
04526 Vector2<kt_int32s> gridIndex(pointX, pointY);
04527 if (IsValidGridIndex(gridIndex))
04528 {
04529 kt_int32s index = GridIndex(gridIndex, false);
04530 T* pGridPointer = GetDataPointer();
04531 pGridPointer[index]++;
04532
04533 if (f != NULL)
04534 {
04535 (*f)(index);
04536 }
04537 }
04538 }
04539 }
04540
04541 protected:
04547 Grid(kt_int32s width, kt_int32s height)
04548 : m_pData(NULL)
04549 , m_pCoordinateConverter(NULL)
04550 {
04551 Resize(width, height);
04552 }
04553
04554 private:
04555 kt_int32s m_Width;
04556 kt_int32s m_Height;
04557 kt_int32s m_WidthStep;
04558 T* m_pData;
04559
04560 CoordinateConverter* m_pCoordinateConverter;
04561 };
04562
04566
04567 class CustomData : public Object
04568 {
04569 public:
04570 KARTO_Object(CustomData)
04571
04572 public:
04573 CustomData()
04574 : Object()
04575 {
04576 }
04577
04578 virtual ~CustomData()
04579 {
04580 }
04581
04582 public:
04583 virtual const std::string Write() const = 0;
04584 virtual void Read(const std::string& rValue) = 0;
04585
04586 private:
04587 CustomData(const CustomData&);
04588 const CustomData& operator=(const CustomData&);
04589 };
04590
04591 typedef std::vector<CustomData*> CustomDataVector;
04592
04596
04600 class KARTO_EXPORT SensorData : public Object
04601 {
04602 public:
04603 KARTO_Object(SensorData);
04604
04605 public:
04609 virtual ~SensorData();
04610
04611 public:
04616 inline kt_int32s GetStateId() const
04617 {
04618 return m_StateId;
04619 }
04620
04625 inline void SetStateId(kt_int32s id)
04626 {
04627 m_StateId = id;
04628 }
04629
04634 inline kt_int32s GetUniqueId() const
04635 {
04636 return m_UniqueId;
04637 }
04638
04643 inline void SetUniqueId(kt_int32u id)
04644 {
04645 m_UniqueId = id;
04646 }
04647
04652 inline kt_double GetTime() const
04653 {
04654 return m_Time;
04655 }
04656
04661 inline void SetTime(kt_double time)
04662 {
04663 m_Time = time;
04664 }
04665
04670 inline const Name& GetSensorName() const
04671 {
04672 return m_SensorName;
04673 }
04674
04679 inline void AddCustomData(CustomData* pCustomData)
04680 {
04681 m_CustomData.push_back(pCustomData);
04682 }
04683
04688 inline const CustomDataVector& GetCustomData() const
04689 {
04690 return m_CustomData;
04691 }
04692
04693 protected:
04694 SensorData(const Name& rSensorName);
04695
04696 private:
04700 SensorData(const SensorData&);
04701
04705 const SensorData& operator=(const SensorData&);
04706
04707 private:
04711 kt_int32s m_StateId;
04712
04716 kt_int32s m_UniqueId;
04717
04721 Name m_SensorName;
04722
04726 kt_double m_Time;
04727
04728 CustomDataVector m_CustomData;
04729 };
04730
04734
04735 typedef std::vector<kt_double> RangeReadingsVector;
04736
04740 class LaserRangeScan : public SensorData
04741 {
04742 public:
04743 KARTO_Object(LaserRangeScan)
04744
04745 public:
04750 LaserRangeScan(const std::string& rSensorName)
04751 : SensorData(rSensorName)
04752 , m_pRangeReadings(NULL)
04753 , m_NumberOfRangeReadings(0)
04754 {
04755 assert(rSensorName != "");
04756 }
04757
04763 LaserRangeScan(const Name& rSensorName, const RangeReadingsVector& rRangeReadings)
04764 : SensorData(rSensorName)
04765 , m_pRangeReadings(NULL)
04766 , m_NumberOfRangeReadings(0)
04767 {
04768 assert(rSensorName.ToString() != "");
04769
04770 SetRangeReadings(rRangeReadings);
04771 }
04772
04776 virtual ~LaserRangeScan()
04777 {
04778 delete [] m_pRangeReadings;
04779 }
04780
04781 public:
04786 inline kt_double* GetRangeReadings() const
04787 {
04788 return m_pRangeReadings;
04789 }
04790
04791 inline void SetRangeReadings(const RangeReadingsVector& rRangeReadings)
04792 {
04793
04794
04795
04796
04797
04798
04799
04800
04801 if (rRangeReadings.size() > 0)
04802 {
04803 if (rRangeReadings.size() != m_NumberOfRangeReadings)
04804 {
04805
04806 delete [] m_pRangeReadings;
04807
04808
04809 m_NumberOfRangeReadings = static_cast<kt_int32u>(rRangeReadings.size());
04810
04811
04812 m_pRangeReadings = new kt_double[m_NumberOfRangeReadings];
04813 }
04814
04815
04816 kt_int32u index = 0;
04817 const_forEach(RangeReadingsVector, &rRangeReadings)
04818 {
04819 m_pRangeReadings[index++] = *iter;
04820 }
04821 }
04822 else
04823 {
04824 delete [] m_pRangeReadings;
04825 m_pRangeReadings = NULL;
04826 }
04827 }
04828
04833 inline LaserRangeFinder* GetLaserRangeFinder() const
04834 {
04835 return SensorManager::GetInstance()->GetSensorByName<LaserRangeFinder>(GetSensorName());
04836 }
04837
04842 inline kt_int32u GetNumberOfRangeReadings() const
04843 {
04844 return m_NumberOfRangeReadings;
04845 }
04846
04847 private:
04848 LaserRangeScan(const LaserRangeScan&);
04849 const LaserRangeScan& operator=(const LaserRangeScan&);
04850
04851 private:
04852 kt_double* m_pRangeReadings;
04853 kt_int32u m_NumberOfRangeReadings;
04854 };
04855
04859
04863 class DrivePose : public SensorData
04864 {
04865 public:
04866 KARTO_Object(DrivePose)
04867
04868 public:
04873 DrivePose(const std::string& rSensorName)
04874 : SensorData(rSensorName)
04875 {
04876 }
04877
04881 virtual ~DrivePose()
04882 {
04883 }
04884
04885 public:
04890 inline const Pose3& GetOdometricPose() const
04891 {
04892 return m_OdometricPose;
04893 }
04894
04899 inline void SetOdometricPose(const Pose3& rPose)
04900 {
04901 m_OdometricPose = rPose;
04902 }
04903
04904 private:
04905 DrivePose(const DrivePose&);
04906 const DrivePose& operator=(const DrivePose&);
04907
04908 private:
04912 Pose3 m_OdometricPose;
04913 };
04914
04918
04925 class LocalizedRangeScan : public LaserRangeScan
04926 {
04927 public:
04928 KARTO_Object(LocalizedRangeScan)
04929
04930 public:
04934 LocalizedRangeScan(const Name& rSensorName, const RangeReadingsVector& rReadings)
04935 : LaserRangeScan(rSensorName, rReadings)
04936 , m_IsDirty(true)
04937 {
04938 }
04939
04943 virtual ~LocalizedRangeScan()
04944 {
04945 }
04946
04947 public:
04952 inline const Pose2& GetOdometricPose() const
04953 {
04954 return m_OdometricPose;
04955 }
04956
04961 inline void SetOdometricPose(const Pose2& rPose)
04962 {
04963 m_OdometricPose = rPose;
04964 }
04965
04974 inline const Pose2& GetCorrectedPose() const
04975 {
04976 return m_CorrectedPose;
04977 }
04978
04983 inline void SetCorrectedPose(const Pose2& rPose)
04984 {
04985 m_CorrectedPose = rPose;
04986
04987 m_IsDirty = true;
04988 }
04989
04993 inline const Pose2& GetBarycenterPose() const
04994 {
04995 if (m_IsDirty)
04996 {
04997
04998 const_cast<LocalizedRangeScan*>(this)->Update();
04999 }
05000
05001 return m_BarycenterPose;
05002 }
05003
05009 inline Pose2 GetReferencePose(kt_bool useBarycenter) const
05010 {
05011 if (m_IsDirty)
05012 {
05013
05014 const_cast<LocalizedRangeScan*>(this)->Update();
05015 }
05016
05017 return useBarycenter ? GetBarycenterPose() : GetSensorPose();
05018 }
05019
05024 inline Pose2 GetSensorPose() const
05025 {
05026 return GetSensorAt(m_CorrectedPose);
05027 }
05028
05033 void SetSensorPose(const Pose2& rScanPose)
05034 {
05035 Pose2 deviceOffsetPose2 = GetLaserRangeFinder()->GetOffsetPose();
05036 kt_double offsetLength = deviceOffsetPose2.GetPosition().Length();
05037 kt_double offsetHeading = deviceOffsetPose2.GetHeading();
05038 kt_double angleoffset = atan2(deviceOffsetPose2.GetY(), deviceOffsetPose2.GetX());
05039 kt_double correctedHeading = math::NormalizeAngle(rScanPose.GetHeading());
05040 Pose2 worldSensorOffset = Pose2(offsetLength * cos(correctedHeading + angleoffset - offsetHeading),
05041 offsetLength * sin(correctedHeading + angleoffset - offsetHeading),
05042 offsetHeading);
05043
05044 m_CorrectedPose = rScanPose - worldSensorOffset;
05045
05046 Update();
05047 }
05048
05054 inline Pose2 GetSensorAt(const Pose2& rPose) const
05055 {
05056 return Transform(rPose).TransformPose(GetLaserRangeFinder()->GetOffsetPose());
05057 }
05058
05063 inline const BoundingBox2& GetBoundingBox() const
05064 {
05065 if (m_IsDirty)
05066 {
05067
05068 const_cast<LocalizedRangeScan*>(this)->Update();
05069 }
05070
05071 return m_BoundingBox;
05072 }
05073
05077 inline const PointVectorDouble& GetPointReadings(kt_bool wantFiltered = false) const
05078 {
05079 if (m_IsDirty)
05080 {
05081
05082 const_cast<LocalizedRangeScan*>(this)->Update();
05083 }
05084
05085 if (wantFiltered == true)
05086 {
05087 return m_PointReadings;
05088 }
05089 else
05090 {
05091 return m_UnfilteredPointReadings;
05092 }
05093 }
05094
05095 private:
05100 void Update()
05101 {
05102 LaserRangeFinder* pLaserRangeFinder = GetLaserRangeFinder();
05103
05104 if (pLaserRangeFinder != NULL)
05105 {
05106 m_PointReadings.clear();
05107 m_UnfilteredPointReadings.clear();
05108
05109 kt_double rangeThreshold = pLaserRangeFinder->GetRangeThreshold();
05110 kt_double minimumAngle = pLaserRangeFinder->GetMinimumAngle();
05111 kt_double angularResolution = pLaserRangeFinder->GetAngularResolution();
05112 Pose2 scanPose = GetSensorPose();
05113
05114
05115 Vector2<kt_double> rangePointsSum;
05116 kt_int32u beamNum = 0;
05117 for (kt_int32u i = 0; i < pLaserRangeFinder->GetNumberOfRangeReadings(); i++, beamNum++)
05118 {
05119 kt_double rangeReading = GetRangeReadings()[i];
05120 if (!math::InRange(rangeReading, pLaserRangeFinder->GetMinimumRange(), rangeThreshold))
05121 {
05122 kt_double angle = scanPose.GetHeading() + minimumAngle + beamNum * angularResolution;
05123
05124 Vector2<kt_double> point;
05125 point.SetX(scanPose.GetX() + (rangeReading * cos(angle)));
05126 point.SetY(scanPose.GetY() + (rangeReading * sin(angle)));
05127
05128 m_UnfilteredPointReadings.push_back(point);
05129 continue;
05130 }
05131
05132 kt_double angle = scanPose.GetHeading() + minimumAngle + beamNum * angularResolution;
05133
05134 Vector2<kt_double> point;
05135 point.SetX(scanPose.GetX() + (rangeReading * cos(angle)));
05136 point.SetY(scanPose.GetY() + (rangeReading * sin(angle)));
05137
05138 m_PointReadings.push_back(point);
05139 m_UnfilteredPointReadings.push_back(point);
05140
05141 rangePointsSum += point;
05142 }
05143
05144
05145 kt_double nPoints = static_cast<kt_double>(m_PointReadings.size());
05146 if (nPoints != 0.0)
05147 {
05148 Vector2<kt_double> averagePosition = Vector2<kt_double>(rangePointsSum / nPoints);
05149 m_BarycenterPose = Pose2(averagePosition, 0.0);
05150 }
05151 else
05152 {
05153 m_BarycenterPose = scanPose;
05154 }
05155
05156
05157 m_BoundingBox = BoundingBox2();
05158 m_BoundingBox.Add(scanPose.GetPosition());
05159 forEach(PointVectorDouble, &m_PointReadings)
05160 {
05161 m_BoundingBox.Add(*iter);
05162 }
05163 }
05164
05165 m_IsDirty = false;
05166 }
05167
05168 private:
05169 LocalizedRangeScan(const LocalizedRangeScan&);
05170 const LocalizedRangeScan& operator=(const LocalizedRangeScan&);
05171
05172 private:
05176 Pose2 m_OdometricPose;
05177
05181 Pose2 m_CorrectedPose;
05182
05186 Pose2 m_BarycenterPose;
05187
05191 PointVectorDouble m_PointReadings;
05192
05196 PointVectorDouble m_UnfilteredPointReadings;
05197
05201 BoundingBox2 m_BoundingBox;
05202
05206 kt_bool m_IsDirty;
05207 };
05208
05209 typedef std::vector<LocalizedRangeScan*> LocalizedRangeScanVector;
05210
05214
05215 class OccupancyGrid;
05216
05217 class KARTO_EXPORT CellUpdater : public Functor
05218 {
05219 public:
05220 CellUpdater(OccupancyGrid* pGrid)
05221 : m_pOccupancyGrid(pGrid)
05222 {
05223 }
05224
05229 virtual void operator() (kt_int32u index);
05230
05231 private:
05232 OccupancyGrid* m_pOccupancyGrid;
05233 };
05234
05238 class OccupancyGrid : public Grid<kt_int8u>
05239 {
05240 friend class CellUpdater;
05241
05242 public:
05246 virtual ~OccupancyGrid()
05247 {
05248 delete m_pCellUpdater;
05249
05250 delete m_pCellPassCnt;
05251 delete m_pCellHitsCnt;
05252
05253 delete m_pMinPassThrough;
05254 delete m_pOccupancyThreshold;
05255 }
05256
05257 public:
05265 OccupancyGrid(kt_int32s width, kt_int32s height, const Vector2<kt_double>& rOffset, kt_double resolution)
05266 : Grid<kt_int8u>(width, height)
05267 , m_pCellPassCnt(Grid<kt_int32u>::CreateGrid(0, 0, resolution))
05268 , m_pCellHitsCnt(Grid<kt_int32u>::CreateGrid(0, 0, resolution))
05269 , m_pCellUpdater(NULL)
05270 {
05271 m_pCellUpdater = new CellUpdater(this);
05272
05273 if (karto::math::DoubleEqual(resolution, 0.0))
05274 {
05275 throw Exception("Resolution cannot be 0");
05276 }
05277
05278 m_pMinPassThrough = new Parameter<kt_int32u>("MinPassThrough", 2);
05279 m_pOccupancyThreshold = new Parameter<kt_double>("OccupancyThreshold", 0.1);
05280
05281 GetCoordinateConverter()->SetScale(1.0 / resolution);
05282 GetCoordinateConverter()->SetOffset(rOffset);
05283 }
05284
05290 static OccupancyGrid* CreateFromScans(const LocalizedRangeScanVector& rScans, kt_double resolution)
05291 {
05292 if (rScans.size() == 0)
05293 {
05294 return NULL;
05295 }
05296
05297 kt_int32s width, height;
05298 Vector2<kt_double> offset;
05299 OccupancyGrid::ComputeDimensions(rScans, resolution, width, height, offset);
05300 OccupancyGrid* pOccupancyGrid = new OccupancyGrid(width, height, offset, resolution);
05301 pOccupancyGrid->CreateFromScans(rScans);
05302
05303 return pOccupancyGrid;
05304 }
05305
05310 OccupancyGrid* Clone() const
05311 {
05312 OccupancyGrid* pOccupancyGrid = new OccupancyGrid(GetWidth(), GetHeight(), GetCoordinateConverter()->GetOffset(), 1.0 / GetCoordinateConverter()->GetScale());
05313 memcpy(pOccupancyGrid->GetDataPointer(), GetDataPointer(), GetDataSize());
05314
05315 pOccupancyGrid->GetCoordinateConverter()->SetSize(GetCoordinateConverter()->GetSize());
05316 pOccupancyGrid->m_pCellPassCnt = m_pCellPassCnt->Clone();
05317 pOccupancyGrid->m_pCellHitsCnt = m_pCellHitsCnt->Clone();
05318
05319 return pOccupancyGrid;
05320 }
05321
05327 virtual kt_bool IsFree(const Vector2<kt_int32s>& rPose) const
05328 {
05329 kt_int8u* pOffsets = (kt_int8u*)GetDataPointer(rPose);
05330 if (*pOffsets == GridStates_Free)
05331 {
05332 return true;
05333 }
05334
05335 return false;
05336 }
05337
05345 virtual kt_double RayCast(const Pose2& rPose2, kt_double maxRange) const
05346 {
05347 double scale = GetCoordinateConverter()->GetScale();
05348
05349 kt_double x = rPose2.GetX();
05350 kt_double y = rPose2.GetY();
05351 kt_double theta = rPose2.GetHeading();
05352
05353 kt_double sinTheta = sin(theta);
05354 kt_double cosTheta = cos(theta);
05355
05356 kt_double xStop = x + maxRange * cosTheta;
05357 kt_double xSteps = 1 + fabs(xStop - x) * scale;
05358
05359 kt_double yStop = y + maxRange * sinTheta;
05360 kt_double ySteps = 1 + fabs(yStop - y) * scale;
05361
05362 kt_double steps = math::Maximum(xSteps, ySteps);
05363 kt_double delta = maxRange / steps;
05364 kt_double distance = delta;
05365
05366 for (kt_int32u i = 1; i < steps; i++)
05367 {
05368 kt_double x1 = x + distance * cosTheta;
05369 kt_double y1 = y + distance * sinTheta;
05370
05371 Vector2<kt_int32s> gridIndex = WorldToGrid(Vector2<kt_double>(x1, y1));
05372 if (IsValidGridIndex(gridIndex) && IsFree(gridIndex))
05373 {
05374 distance = (i + 1) * delta;
05375 }
05376 else
05377 {
05378 break;
05379 }
05380 }
05381
05382 return (distance < maxRange)? distance : maxRange;
05383 }
05384
05385 virtual Grid<kt_int32u>* GetCellHitsCounts()
05386 {
05387 return m_pCellHitsCnt;
05388 }
05389
05390 virtual Grid<kt_int32u>* GetCellPassCounts()
05391 {
05392 return m_pCellPassCnt;
05393 }
05394
05395 protected:
05396 static void ComputeDimensions(const LocalizedRangeScanVector& rScans, kt_double resolution, kt_int32s& rWidth, kt_int32s& rHeight, Vector2<kt_double>& rOffset)
05397 {
05398 BoundingBox2 boundingBox;
05399 const_forEach(LocalizedRangeScanVector, &rScans)
05400 {
05401 boundingBox.Add((*iter)->GetBoundingBox());
05402 }
05403
05404 kt_double scale = 1.0 / resolution;
05405 Size2<kt_double> size = boundingBox.GetSize();
05406
05407 rWidth = static_cast<kt_int32s>(math::Round(size.GetWidth() * scale));
05408 rHeight = static_cast<kt_int32s>(math::Round(size.GetHeight() * scale));
05409 rOffset = boundingBox.GetMinimum();
05410 }
05411
05416 virtual void CreateFromScans(const LocalizedRangeScanVector& rScans)
05417 {
05418 m_pCellPassCnt->Resize(GetWidth(), GetHeight());
05419 m_pCellPassCnt->GetCoordinateConverter()->SetOffset(GetCoordinateConverter()->GetOffset());
05420
05421 m_pCellHitsCnt->Resize(GetWidth(), GetHeight());
05422 m_pCellHitsCnt->GetCoordinateConverter()->SetOffset(GetCoordinateConverter()->GetOffset());
05423
05424 const_forEach(LocalizedRangeScanVector, &rScans)
05425 {
05426 LocalizedRangeScan* pScan = *iter;
05427 AddScan(pScan);
05428 }
05429
05430 Update();
05431 }
05432
05440 virtual kt_bool AddScan(LocalizedRangeScan* pScan, kt_bool doUpdate = false)
05441 {
05442 kt_double rangeThreshold = pScan->GetLaserRangeFinder()->GetRangeThreshold();
05443 kt_double maxRange = pScan->GetLaserRangeFinder()->GetMaximumRange();
05444
05445 Vector2<kt_double> scanPosition = pScan->GetSensorPose().GetPosition();
05446
05447
05448 const PointVectorDouble& rPointReadings = pScan->GetPointReadings(false);
05449
05450 kt_bool isAllInMap = true;
05451
05452
05453 int pointIndex = 0;
05454 const_forEachAs(PointVectorDouble, &rPointReadings, pointsIter)
05455 {
05456 Vector2<kt_double> point = *pointsIter;
05457 kt_double rangeReading = pScan->GetRangeReadings()[pointIndex];
05458 kt_bool isEndPointValid = rangeReading < (rangeThreshold - KT_TOLERANCE);
05459
05460 if (rangeReading >= maxRange)
05461 {
05462
05463 pointIndex++;
05464 continue;
05465 }
05466 else if (rangeReading >= rangeThreshold)
05467 {
05468
05469 kt_double ratio = rangeThreshold / rangeReading;
05470 kt_double dx = point.GetX() - scanPosition.GetX();
05471 kt_double dy = point.GetY() - scanPosition.GetY();
05472 point.SetX(scanPosition.GetX() + ratio * dx);
05473 point.SetY(scanPosition.GetY() + ratio * dy);
05474 }
05475
05476 kt_bool isInMap = RayTrace(scanPosition, point, isEndPointValid, doUpdate);
05477 if (!isInMap)
05478 {
05479 isAllInMap = false;
05480 }
05481
05482 pointIndex++;
05483 }
05484
05485 return isAllInMap;
05486 }
05487
05498 virtual kt_bool RayTrace(const Vector2<kt_double>& rWorldFrom, const Vector2<kt_double>& rWorldTo, kt_bool isEndPointValid, kt_bool doUpdate = false)
05499 {
05500 assert(m_pCellPassCnt != NULL && m_pCellHitsCnt != NULL);
05501
05502 Vector2<kt_int32s> gridFrom = m_pCellPassCnt->WorldToGrid(rWorldFrom);
05503 Vector2<kt_int32s> gridTo = m_pCellPassCnt->WorldToGrid(rWorldTo);
05504
05505 CellUpdater* pCellUpdater = doUpdate ? m_pCellUpdater : NULL;
05506 m_pCellPassCnt->TraceLine(gridFrom.GetX(), gridFrom.GetY(), gridTo.GetX(), gridTo.GetY(), pCellUpdater);
05507
05508
05509 if (isEndPointValid)
05510 {
05511 if (m_pCellPassCnt->IsValidGridIndex(gridTo))
05512 {
05513 kt_int32s index = m_pCellPassCnt->GridIndex(gridTo, false);
05514
05515 kt_int32u* pCellPassCntPtr = m_pCellPassCnt->GetDataPointer();
05516 kt_int32u* pCellHitCntPtr = m_pCellHitsCnt->GetDataPointer();
05517
05518
05519 pCellPassCntPtr[index]++;
05520 pCellHitCntPtr[index]++;
05521
05522 if (doUpdate)
05523 {
05524 (*m_pCellUpdater)(index);
05525 }
05526 }
05527 }
05528
05529 return m_pCellPassCnt->IsValidGridIndex(gridTo);
05530 }
05531
05538 virtual void UpdateCell(kt_int8u* pCell, kt_int32u cellPassCnt, kt_int32u cellHitCnt)
05539 {
05540 if (cellPassCnt > m_pMinPassThrough->GetValue())
05541 {
05542 kt_double hitRatio = static_cast<kt_double>(cellHitCnt) / static_cast<kt_double>(cellPassCnt);
05543
05544 if (hitRatio > m_pOccupancyThreshold->GetValue())
05545 {
05546 *pCell = GridStates_Occupied;
05547 }
05548 else
05549 {
05550 *pCell = GridStates_Free;
05551 }
05552 }
05553 }
05554
05558 virtual void Update()
05559 {
05560 assert(m_pCellPassCnt != NULL && m_pCellHitsCnt != NULL);
05561
05562
05563 Clear();
05564
05565
05566 kt_int8u* pDataPtr = GetDataPointer();
05567 kt_int32u* pCellPassCntPtr = m_pCellPassCnt->GetDataPointer();
05568 kt_int32u* pCellHitCntPtr = m_pCellHitsCnt->GetDataPointer();
05569
05570 kt_int32u nBytes = GetDataSize();
05571 for (kt_int32u i = 0; i < nBytes; i++, pDataPtr++, pCellPassCntPtr++, pCellHitCntPtr++)
05572 {
05573 UpdateCell(pDataPtr, *pCellPassCntPtr, *pCellHitCntPtr);
05574 }
05575 }
05576
05582 virtual void Resize(kt_int32s width, kt_int32s height)
05583 {
05584 Grid<kt_int8u>::Resize(width, height);
05585 m_pCellPassCnt->Resize(width, height);
05586 m_pCellHitsCnt->Resize(width, height);
05587 }
05588
05589 protected:
05590
05591 Grid<kt_int32u>* m_pCellPassCnt;
05592
05593
05594 Grid<kt_int32u>* m_pCellHitsCnt;
05595
05596 private:
05600 OccupancyGrid(const OccupancyGrid&);
05601
05605 const OccupancyGrid& operator=(const OccupancyGrid&);
05606
05607 private:
05608 CellUpdater* m_pCellUpdater;
05609
05611
05612
05613
05614
05615
05616 Parameter<kt_int32u>* m_pMinPassThrough;
05617
05618
05619 Parameter<kt_double>* m_pOccupancyThreshold;
05620 };
05621
05625
05631 class DatasetInfo : public Object
05632 {
05633 public:
05634 KARTO_Object(DatasetInfo)
05635
05636 public:
05637 DatasetInfo()
05638 : Object()
05639 {
05640 m_pTitle = new Parameter<std::string>("Title", "", GetParameterManager());
05641 m_pAuthor = new Parameter<std::string>("Author", "", GetParameterManager());
05642 m_pDescription = new Parameter<std::string>("Description", "", GetParameterManager());
05643 m_pCopyright = new Parameter<std::string>("Copyright", "", GetParameterManager());
05644 }
05645
05646 virtual ~DatasetInfo()
05647 {
05648 }
05649
05650 public:
05654 const std::string& GetTitle() const
05655 {
05656 return m_pTitle->GetValue();
05657 }
05658
05662 const std::string& GetAuthor() const
05663 {
05664 return m_pAuthor->GetValue();
05665 }
05666
05670 const std::string& GetDescription() const
05671 {
05672 return m_pDescription->GetValue();
05673 }
05674
05678 const std::string& GetCopyright() const
05679 {
05680 return m_pCopyright->GetValue();
05681 }
05682
05683 private:
05684 DatasetInfo(const DatasetInfo&);
05685 const DatasetInfo& operator=(const DatasetInfo&);
05686
05687 private:
05688 Parameter<std::string>* m_pTitle;
05689 Parameter<std::string>* m_pAuthor;
05690 Parameter<std::string>* m_pDescription;
05691 Parameter<std::string>* m_pCopyright;
05692 };
05693
05697
05702 class Dataset
05703 {
05704 public:
05708 Dataset()
05709 : m_pDatasetInfo(NULL)
05710 {
05711 }
05712
05716 virtual ~Dataset()
05717 {
05718 Clear();
05719 }
05720
05721 public:
05726 void Add(Object* pObject)
05727 {
05728 if (pObject != NULL)
05729 {
05730 if (dynamic_cast<Sensor*>(pObject))
05731 {
05732 Sensor* pSensor = dynamic_cast<Sensor*>(pObject);
05733 if(pSensor != NULL)
05734 {
05735 m_SensorNameLookup[pSensor->GetName()] = pSensor;
05736
05737 karto::SensorManager::GetInstance()->RegisterSensor(pSensor);
05738 }
05739
05740 m_Objects.push_back(pObject);
05741 }
05742 else if (dynamic_cast<SensorData*>(pObject))
05743 {
05744 SensorData* pSensorData = dynamic_cast<SensorData*>(pObject);
05745 m_Objects.push_back(pSensorData);
05746 }
05747 else if (dynamic_cast<DatasetInfo*>(pObject))
05748 {
05749 m_pDatasetInfo = dynamic_cast<DatasetInfo*>(pObject);
05750 }
05751 else
05752 {
05753 m_Objects.push_back(pObject);
05754 }
05755 }
05756 }
05757
05762 inline const ObjectVector& GetObjects() const
05763 {
05764 return m_Objects;
05765 }
05766
05767 inline DatasetInfo* GetDatasetInfo()
05768 {
05769 return m_pDatasetInfo;
05770 }
05771
05772 inline Sensor* GetSensor(const std::string& rName)
05773 {
05774 if(m_SensorNameLookup.find(rName) != m_SensorNameLookup.end())
05775 {
05776 return m_SensorNameLookup[rName];
05777 }
05778
05779 return NULL;
05780 }
05781
05785 virtual void Clear()
05786 {
05787 for (std::map<Name, Sensor*>::iterator iter = m_SensorNameLookup.begin(); iter != m_SensorNameLookup.end(); iter++)
05788 {
05789 karto::SensorManager::GetInstance()->UnregisterSensor(iter->second);
05790 }
05791
05792 forEach(ObjectVector, &m_Objects)
05793 {
05794 delete *iter;
05795 }
05796
05797 m_Objects.clear();
05798
05799 if (m_pDatasetInfo != NULL)
05800 {
05801 delete m_pDatasetInfo;
05802 m_pDatasetInfo = NULL;
05803 }
05804 }
05805
05806 private:
05807 std::map<Name, Sensor*> m_SensorNameLookup;
05808 ObjectVector m_Objects;
05809 DatasetInfo* m_pDatasetInfo;
05810 };
05811
05815
05820 class LookupArray
05821 {
05822 public:
05827 LookupArray()
05828 : m_pArray(NULL)
05829 , m_Capacity(0)
05830 , m_Size(0)
05831 {
05832 }
05833
05837 virtual ~LookupArray()
05838 {
05839 assert(m_pArray != NULL);
05840
05841 delete[] m_pArray;
05842 m_pArray = NULL;
05843 }
05844
05845 public:
05849 void Clear()
05850 {
05851 memset(m_pArray, 0, sizeof(kt_int32s) * m_Capacity);
05852 }
05853
05858 kt_int32u GetSize() const
05859 {
05860 return m_Size;
05861 }
05862
05867 void SetSize(kt_int32u size)
05868 {
05869 assert(size != 0);
05870
05871 if (size > m_Capacity)
05872 {
05873 if (m_pArray != NULL)
05874 {
05875 delete [] m_pArray;
05876 }
05877 m_Capacity = size;
05878 m_pArray = new kt_int32s[m_Capacity];
05879 }
05880
05881 m_Size = size;
05882 }
05883
05889 inline kt_int32s& operator [] (kt_int32u index)
05890 {
05891 assert(index < m_Size);
05892
05893 return m_pArray[index];
05894 }
05895
05901 inline kt_int32s operator [] (kt_int32u index) const
05902 {
05903 assert(index < m_Size);
05904
05905 return m_pArray[index];
05906 }
05907
05912 inline kt_int32s* GetArrayPointer()
05913 {
05914 return m_pArray;
05915 }
05916
05921 inline kt_int32s* GetArrayPointer() const
05922 {
05923 return m_pArray;
05924 }
05925
05926 private:
05927 kt_int32s* m_pArray;
05928 kt_int32u m_Capacity;
05929 kt_int32u m_Size;
05930 };
05931
05935
05949 template<typename T>
05950 class GridIndexLookup
05951 {
05952 public:
05953 GridIndexLookup(Grid<T>* pGrid)
05954 : m_pGrid(pGrid)
05955 , m_Capacity(0)
05956 , m_Size(0)
05957 , m_ppLookupArray(NULL)
05958 {
05959 }
05960
05964 virtual ~GridIndexLookup()
05965 {
05966 DestroyArrays();
05967 }
05968
05969 public:
05975 const LookupArray* GetLookupArray(kt_int32u index) const
05976 {
05977 assert(math::IsUpTo(index, m_Size));
05978
05979 return m_ppLookupArray[index];
05980 }
05981
05982 const std::vector<kt_double>& GetAngles() const
05983 {
05984 return m_Angles;
05985 }
05986
05994 void ComputeOffsets(LocalizedRangeScan* pScan, kt_double angleCenter, kt_double angleOffset, kt_double angleResolution)
05995 {
05996 assert(angleOffset != 0.0);
05997 assert(angleResolution != 0.0);
05998
05999 kt_int32u nAngles = static_cast<kt_int32u>(math::Round(angleOffset * 2.0 / angleResolution) + 1);
06000 SetSize(nAngles);
06001
06003
06004
06005 const PointVectorDouble& rPointReadings = pScan->GetPointReadings();
06006
06007
06008 Transform transform(pScan->GetSensorPose());
06009
06010 Pose2Vector localPoints;
06011 const_forEach(PointVectorDouble, &rPointReadings)
06012 {
06013
06014 Pose2 vec = transform.InverseTransformPose(Pose2(*iter, 0.0));
06015 localPoints.push_back(vec);
06016 }
06017
06019
06020 kt_double angle = 0.0;
06021 kt_double startAngle = angleCenter - angleOffset;
06022 for (kt_int32u angleIndex = 0; angleIndex < nAngles; angleIndex++)
06023 {
06024 angle = startAngle + angleIndex * angleResolution;
06025 ComputeOffsets(angleIndex, angle, localPoints);
06026 }
06027
06028 }
06029
06030 private:
06037 void ComputeOffsets(kt_int32u angleIndex, kt_double angle, const Pose2Vector& rLocalPoints)
06038 {
06039 m_ppLookupArray[angleIndex]->SetSize(static_cast<kt_int32u>(rLocalPoints.size()));
06040 m_Angles.at(angleIndex) = angle;
06041
06042
06043
06044
06045 const Vector2<kt_double>& rGridOffset = m_pGrid->GetCoordinateConverter()->GetOffset();
06046
06047 kt_double cosine = cos(angle);
06048 kt_double sine = sin(angle);
06049
06050 kt_int32u readingIndex = 0;
06051
06052 kt_int32s* pAngleIndexPointer = m_ppLookupArray[angleIndex]->GetArrayPointer();
06053
06054 const_forEach(Pose2Vector, &rLocalPoints)
06055 {
06056 const Vector2<kt_double>& rPosition = iter->GetPosition();
06057
06058
06059 Vector2<kt_double> offset;
06060 offset.SetX(cosine * rPosition.GetX() - sine * rPosition.GetY());
06061 offset.SetY( sine * rPosition.GetX() + cosine * rPosition.GetY());
06062
06063
06064 Vector2<kt_int32s> gridPoint = m_pGrid->WorldToGrid(offset + rGridOffset);
06065
06066
06067 kt_int32s lookupIndex = m_pGrid->Grid<T>::GridIndex(gridPoint, false);
06068
06069 pAngleIndexPointer[readingIndex] = lookupIndex;
06070
06071 readingIndex++;
06072 }
06073 assert(readingIndex == rLocalPoints.size());
06074 }
06075
06080 void SetSize(kt_int32u size)
06081 {
06082 assert(size != 0);
06083
06084 if (size > m_Capacity)
06085 {
06086 if (m_ppLookupArray != NULL)
06087 {
06088 DestroyArrays();
06089 }
06090
06091 m_Capacity = size;
06092 m_ppLookupArray = new LookupArray*[m_Capacity];
06093 for (kt_int32u i = 0; i < m_Capacity; i++)
06094 {
06095 m_ppLookupArray[i] = new LookupArray();
06096 }
06097 }
06098
06099 m_Size = size;
06100
06101 m_Angles.resize(size);
06102 }
06103
06107 void DestroyArrays()
06108 {
06109 for (kt_int32u i = 0; i < m_Capacity; i++)
06110 {
06111 delete m_ppLookupArray[i];
06112 }
06113
06114 delete[] m_ppLookupArray;
06115 m_ppLookupArray = NULL;
06116 }
06117
06118 private:
06119 Grid<T>* m_pGrid;
06120
06121 kt_int32u m_Capacity;
06122 kt_int32u m_Size;
06123
06124 LookupArray **m_ppLookupArray;
06125
06126
06127 std::vector<kt_double> m_Angles;
06128 };
06129
06133
06134 inline Pose2::Pose2(const Pose3& rPose)
06135 : m_Position(rPose.GetPosition().GetX(), rPose.GetPosition().GetY())
06136 {
06137 kt_double t1, t2;
06138
06139
06140 rPose.GetOrientation().ToEulerAngles(m_Heading, t1, t2);
06141 }
06142
06146
06147 template<typename T>
06148 inline void Object::SetParameter(const std::string& rName, T value)
06149 {
06150 AbstractParameter* pParameter = GetParameter(rName);
06151 if (pParameter != NULL)
06152 {
06153 std::stringstream stream;
06154 stream << value;
06155 pParameter->SetValueFromString(stream.str());
06156 }
06157 else
06158 {
06159 throw karto::Exception("Parameter does not exist: " + rName);
06160 }
06161 }
06162
06163 template<>
06164 inline void Object::SetParameter(const std::string& rName, kt_bool value)
06165 {
06166 AbstractParameter* pParameter = GetParameter(rName);
06167 if (pParameter != NULL)
06168 {
06169 pParameter->SetValueFromString(value ? "true" : "false");
06170 }
06171 else
06172 {
06173 throw karto::Exception("Parameter does not exist: " + rName);
06174 }
06175 }
06176 }
06177
06178 #endif // __KARTO_KARTO__