Namespaces | Classes | Macros | Typedefs | Enumerations | Functions | Variables | Friends
OpenKarto Module

Namespaces

 karto::gps
 
 karto::math
 

Classes

class  karto::AbstractEvent< TArgs >
 
class  karto::AbstractGpsEstimationManager
 
class  karto::AbstractParameter
 
class  karto::Any
 
class  karto::BasicEvent< TArgs >
 
class  karto::BoundingBox2
 
class  karto::BoundingBox3
 
class  karto::CellUpdater
 
class  karto::Color
 
class  karto::ConstListIterator< T >
 
class  karto::CoordinateConverter
 
class  karto::CorrelationGrid
 
class  karto::Dataset
 
class  karto::Drive
 
class  karto::DrivePose
 
class  karto::Edge< T >
 
class  karto::EdgeLabel
 
struct  karto::EnumPair
 
class  karto::EventArguments
 
class  karto::Exception
 
struct  karto::FindByName
 
struct  karto::FindByValue
 
class  karto::Functor
 
class  karto::Graph< T >
 
class  karto::GraphTraversal< T >
 
class  karto::Grid< T >
 
class  karto::GridIndexLookup< T >
 
class  karto::Identifier
 
class  karto::LaserRangeFinder
 
class  karto::LaserRangeScan
 
class  karto::LinkInfo
 
class  karto::List< T >
 
class  karto::ListIterator< T >
 
class  karto::LocalizedLaserScan
 
class  karto::LocalizedObject
 
class  karto::LocalizedPointScan
 
class  karto::LocalizedRangeScan
 
class  karto::LogMessageArguments
 
class  karto::LookupArray
 
class  karto::MapperEventArguments
 
class  karto::MapperGraph
 
class  karto::MapperSensorManager
 
class  karto::Matrix3
 
class  karto::MetaAttribute
 
class  karto::MetaClass
 
class  karto::MetaClassHelper< T >
 
class  karto::MetaEnum
 
class  karto::Module
 
class  karto::Mutex
 
class  karto::Object
 
class  karto::OccupancyGrid
 
class  karto::OpenMapper
 
class  karto::Pair< U, V >
 
class  karto::Parameter< T >
 
class  karto::ParameterDescription
 
class  karto::ParameterEnum
 
class  karto::ParameterSet
 
class  karto::Pose2
 
class  karto::Pose3
 
class  karto::Quaternion
 
class  karto::Rectangle2< T >
 
class  karto::Referenced
 
class  karto::ScanMatcher
 
class  karto::ScanMatcherGridSet
 
class  karto::ScanSolver
 
class  karto::Sensor
 
class  karto::SensorData
 
class  karto::SensorRegistry
 
class  karto::Size2< T >
 
class  karto::Size3< T >
 
class  karto::SmartPointer< T >
 
class  karto::String
 
class  karto::StringBuilder
 
class  karto::StringHelper
 
class  karto::Transform
 
class  karto::Vector2< T >
 
class  karto::Vector3< T >
 
class  karto::Vector4< T >
 
class  karto::Vertex< T >
 
class  karto::Visitor< T >
 

Macros

#define const_forEach(listtype, list)   for ( listtype::const_iterator iter = (list)->begin(); iter != (list)->end(); ++iter )
 
#define const_forEachAs(listtype, list, iter)   for ( listtype::const_iterator iter = (list)->begin(); iter != (list)->end(); ++iter )
 
#define const_forEachR(listtype, list)   for ( listtype::const_reverse_iterator iter = (list)->rbegin(); iter != (list)->rend(); ++iter )
 
#define forEach(listtype, list)   for ( listtype::iterator iter = (list)->begin(); iter != (list)->end(); ++iter )
 
#define forEachAs(listtype, list, iter)   for ( listtype::iterator iter = (list)->begin(); iter != (list)->end(); ++iter )
 
#define forEachR(listtype, list)   for ( listtype::reverse_iterator iter = (list)->rbegin(); iter != (list)->rend(); ++iter )
 
#define KARTO_AUTO_TYPE(type, registerFunc)
 
#define karto_const_forEach(listtype, list)   for ( listtype::ConstIterator iter = (list)->GetConstIterator(); iter.HasNext(); iter.Next())
 
#define karto_const_forEachAs(listtype, list, iter)   for ( listtype::ConstIterator iter = (list)->GetConstIterator(); iter.HasNext(); iter.Next())
 
#define KARTO_DEPRECATED
 
#define KARTO_EXPORT
 
#define KARTO_FORCEINLINE
 
#define karto_forEach(listtype, list)   for ( listtype::Iterator iter = (list)->GetIterator(); iter.HasNext(); iter.Next())
 
#define karto_forEachAs(listtype, list, iter)   for ( listtype::Iterator iter = (list)->GetIterator(); iter.HasNext(); iter.Next())
 
#define KARTO_RTTI()
 
#define KARTO_TYPE(type)
 
#define KARTO_TYPECHECKCAST(__Name__)
 

Typedefs

typedef SmartPointer< Dataset > karto::DatasetPtr
 
typedef List< kt_doublekarto::DoubleList
 
typedef List< EnumPair > karto::EnumPairList
 
typedef bool kt_bool
 
typedef char kt_char
 
typedef double kt_double
 
typedef float kt_float
 
typedef int16_t kt_int16s
 
typedef uint16_t kt_int16u
 
typedef int32_t kt_int32s
 
typedef uint32_t kt_int32u
 
typedef signed long long kt_int64s
 
typedef unsigned long long kt_int64u
 
typedef int8_t kt_int8s
 
typedef uint8_t kt_int8u
 
typedef kt_int32u kt_objecttype
 
typedef std::size_t kt_size_t
 
typedef kt_int64s kt_tick
 
typedef SmartPointer< LaserRangeFinder > karto::LaserRangeFinderPtr
 
typedef List< LocalizedLaserScanPtr > karto::LocalizedLaserScanList
 
typedef SmartPointer< LocalizedLaserScan > karto::LocalizedLaserScanPtr
 
typedef List< LocalizedObjectPtr > karto::LocalizedObjectList
 
typedef SmartPointer< LocalizedObject > karto::LocalizedObjectPtr
 
typedef List< ObjectPtr > karto::ObjectList
 
typedef SmartPointer< Object > karto::ObjectPtr
 
typedef SmartPointer< OccupancyGrid > karto::OccupancyGridPtr
 
typedef List< SmartPointer< AbstractParameter > > karto::ParameterList
 
typedef SmartPointer< ParameterSet > karto::ParameterSetPtr
 
typedef List< Pose2 > karto::Pose2List
 
typedef List< kt_doublekarto::RangeReadingsList
 
typedef List< SensorPtr > karto::SensorList
 
typedef SmartPointer< Sensor > karto::SensorPtr
 
typedef Vector2< kt_doublekarto::Vector2d
 
typedef List< Vector2d > karto::Vector2dList
 
typedef Vector2< kt_int32skarto::Vector2i
 
typedef Vector2< kt_int32ukarto::Vector2iu
 
typedef Vector3< kt_doublekarto::Vector3d
 
typedef Vector3< kt_int32skarto::Vector3i
 
typedef Vector3< kt_int32ukarto::Vector3iu
 
typedef Vector4< kt_doublekarto::Vector4d
 
typedef Vector4< kt_int32skarto::Vector4i
 
typedef Vector4< kt_int32ukarto::Vector4iu
 

Enumerations

enum  karto::GridStates { karto::GridStates_Unknown = 0, karto::GridStates_Occupied = 100, karto::GridStates_Free = 255 }
 
enum  karto::LaserRangeFinderType {
  karto::LaserRangeFinder_Custom = 0, karto::LaserRangeFinder_Sick_LMS100 = 1, karto::LaserRangeFinder_Sick_LMS200 = 2, karto::LaserRangeFinder_Sick_LMS291 = 3,
  karto::LaserRangeFinder_Hokuyo_UTM_30LX = 4, karto::LaserRangeFinder_Hokuyo_URG_04LX = 5
}
 
enum  karto::LogLevel {
  karto::LOG_NONE = 0, karto::LOG_FATAL = 1, karto::LOG_ERROR = 3, karto::LOG_WARNING = 4,
  karto::LOG_INFORMATION = 6, karto::LOG_DEBUG = 7
}
 
enum  karto::ParameterFlags { karto::ParameterFlag_Read = 0x01, karto::ParameterFlag_Write = 0x02, karto::ParameterFlag_Hidden = 0x08, karto::ParameterFlag_System = 0x10 }
 

Functions

template<class T >
karto::math::AlignValue (size_t value, size_t alignValue=8)
 
template<typename T >
T * karto::any_cast (Any *pAny)
 
template<typename T >
const T * karto::any_cast (const Any *pAny)
 
template<typename T >
karto::any_cast (const Any &rAny)
 
template<typename T >
const T & karto::math::Clip (const T &n, const T &minValue, const T &maxValue)
 
kt_double karto::math::DegreesToRadians (kt_double degrees)
 
template<class TObj , class TArgs >
static Delegate< TObj, TArgs, true > karto::delegate (TObj *pObj, void(TObj::*NotifyMethod)(const void *, TArgs &))
 
template<class TObj , class TArgs >
static Delegate< TObj, TArgs, false > karto::delegate (TObj *pObj, void(TObj::*NotifyMethod)(TArgs &))
 
template<class TArgs >
static FunctionDelegate< TArgs, true, true > karto::delegate (void(*NotifyMethod)(const void *, TArgs &))
 
template<class TArgs >
static FunctionDelegate< TArgs, true, false > karto::delegate (void(*NotifyMethod)(void *, TArgs &))
 
template<class TArgs >
static FunctionDelegate< TArgs, false > karto::delegate (void(*NotifyMethod)(TArgs &))
 
kt_bool karto::math::DoubleEqual (kt_double a, kt_double b)
 
template<typename T >
static kt_bool karto::FromString (const String &rStringValue, Vector3< T > &rValue)
 
T * karto::SmartPointer< T >::Get () const
 
LogLevel karto::GetLogLevel ()
 
const MetaClass & karto::GetMetaClassByIndex (kt_size_t index)
 
const MetaClass & karto::GetMetaClassByName (const karto::String &rName)
 
template<typename T >
const MetaClass & karto::GetMetaClassByObject (const T &rObject)
 
template<typename T >
const MetaClass & karto::GetMetaClassByType ()
 
const MetaEnum & karto::GetMetaEnumByIndex (kt_size_t index)
 
const MetaEnum & karto::GetMetaEnumByName (const karto::String &rName)
 
template<typename T >
const MetaEnum & karto::GetMetaEnumByObject (const T &rObject)
 
template<typename T >
const MetaEnum & karto::GetMetaEnumByType ()
 
kt_size_t karto::GetRegisteredMetaClassSize ()
 
kt_size_t karto::GetRegisteredMetaEnumSize ()
 
template<typename T >
kt_bool karto::math::InRange (const T &value, const T &a, const T &b)
 
kt_bool karto::IsLocalizedLaserScan (Object *pObject)
 
template<typename T >
kt_bool karto::math::IsUpTo (const T &value, const T &maximum)
 
kt_bool karto::SmartPointer< T >::IsValid () const
 
 karto::KARTO_AUTO_TYPE (LaserRangeFinderType,&RegisterLaserRangeFinderType)
 
 karto::KARTO_TYPE (Sensor)
 
 karto::KARTO_TYPE (Object)
 
 karto::KARTO_TYPE (Drive)
 
 karto::KARTO_TYPE (SensorData)
 
 karto::KARTO_TYPE (OccupancyGrid)
 
 karto::KARTO_TYPE (LaserRangeScan)
 
 karto::KARTO_TYPE (AbstractParameter)
 
 karto::KARTO_TYPE (DrivePose)
 
 karto::KARTO_TYPE (LaserRangeFinder)
 
 karto::KARTO_TYPE (Grid< kt_int8u >)
 
 karto::KARTO_TYPE (Grid< kt_int32u >)
 
 karto::KARTO_TYPE (Grid< kt_float >)
 
 karto::KARTO_TYPE (Grid< kt_double >)
 
 karto::KARTO_TYPE (LocalizedObject)
 
 karto::KARTO_TYPE (Parameter< kt_bool >)
 
 karto::KARTO_TYPE (Parameter< kt_char >)
 
 karto::KARTO_TYPE (Parameter< kt_int8s >)
 
 karto::KARTO_TYPE (Parameter< kt_int8u >)
 
 karto::KARTO_TYPE (Parameter< kt_int16s >)
 
 karto::KARTO_TYPE (Parameter< kt_int16u >)
 
 karto::KARTO_TYPE (Parameter< kt_int32s >)
 
 karto::KARTO_TYPE (Parameter< kt_int32u >)
 
 karto::KARTO_TYPE (Parameter< kt_int64s >)
 
 karto::KARTO_TYPE (Parameter< kt_int64u >)
 
 karto::KARTO_TYPE (Parameter< kt_float >)
 
 karto::KARTO_TYPE (Parameter< kt_double >)
 
 karto::KARTO_TYPE (Parameter< karto::String >)
 
 karto::KARTO_TYPE (Parameter< karto::Size2< kt_int32s > >)
 
 karto::KARTO_TYPE (Parameter< karto::Size2< kt_int32u > >)
 
 karto::KARTO_TYPE (Parameter< karto::Size2< kt_double > >)
 
 karto::KARTO_TYPE (Parameter< karto::Vector2i >)
 
 karto::KARTO_TYPE (Parameter< karto::Vector3i >)
 
 karto::KARTO_TYPE (Parameter< karto::Vector4i >)
 
 karto::KARTO_TYPE (Parameter< karto::Vector2< kt_int32u > >)
 
 karto::KARTO_TYPE (Parameter< karto::Vector3iu >)
 
 karto::KARTO_TYPE (Parameter< karto::Vector4iu >)
 
 karto::KARTO_TYPE (Parameter< karto::Vector2< kt_double > >)
 
 karto::KARTO_TYPE (Parameter< karto::Vector3d >)
 
 karto::KARTO_TYPE (Parameter< karto::Vector4d >)
 
 karto::KARTO_TYPE (Parameter< karto::Quaternion >)
 
 karto::KARTO_TYPE (Parameter< karto::Color >)
 
 karto::KARTO_TYPE (Parameter< karto::Pose2 >)
 
 karto::KARTO_TYPE (Parameter< karto::Pose3 >)
 
 karto::KARTO_TYPE (Parameter< karto::gps::PointGps >)
 
 karto::KARTO_TYPE (LocalizedLaserScan)
 
 karto::KARTO_TYPE (ParameterEnum)
 
 karto::KARTO_TYPE (LocalizedPointScan)
 
 karto::KARTO_TYPE (LocalizedRangeScan)
 
void karto::Log (LogLevel level, const karto::String &rMessage)
 
template<typename T >
const T & karto::math::Maximum (const T &value1, const T &value2)
 
template<typename T >
const T & karto::math::Minimum (const T &value1, const T &value2)
 
kt_double karto::math::NormalizeAngle (kt_double angle)
 
kt_double karto::math::NormalizeAngleDifference (kt_double minuend, kt_double subtrahend)
 
 karto::SmartPointer< T >::operator T * () const
 
T & karto::SmartPointer< T >::operator* () const
 
T * karto::SmartPointer< T >::operator-> () const
 
SmartPointer & karto::SmartPointer< T >::operator= (const SmartPointer &rOther)
 
SmartPointer & karto::SmartPointer< T >::operator= (T *pPointer)
 
template<class Other >
SmartPointer & karto::SmartPointer< T >::operator= (const SmartPointer< Other > &rOther)
 
kt_double karto::math::RadiansToDegrees (kt_double radians)
 
KARTO_EXPORT void karto::RegisterLaserRangeFinderType ()
 
void karto::SmartPointer< T >::Release ()
 
kt_double karto::math::Round (kt_double value)
 
void karto::SetLogLevel (LogLevel level)
 
 karto::SmartPointer< T >::SmartPointer ()
 
 karto::SmartPointer< T >::SmartPointer (const SmartPointer &rOther)
 
template<class Other >
 karto::SmartPointer< T >::SmartPointer (const SmartPointer< Other > &rOther)
 
 karto::SmartPointer< T >::SmartPointer (T *pPointer)
 
template<typename T >
karto::math::Square (T value)
 
template<class T >
void karto::math::Swap (T &x, T &y)
 
template<typename T >
static String karto::StringHelper::ToString (const Size2< T > &rValue)
 
template<typename T >
static String karto::StringHelper::ToString (const Vector2< T > &rValue)
 
template<typename T >
static String karto::StringHelper::ToString (const Vector3< T > &rValue)
 
template<typename T >
static String karto::StringHelper::ToString (const Vector4< T > &rValue)
 
virtual karto::SmartPointer< T >::~SmartPointer ()
 

Variables

const kt_double karto::KT_180_PI = 57.29577951308232087685
 
const kt_double karto::KT_2PI = 6.28318530717958647692
 
const kt_double karto::KT_PI = 3.14159265358979323846
 
const kt_double karto::KT_PI_180 = 0.01745329251994329577
 
const kt_double karto::KT_PI_2 = 1.57079632679489661923
 
const kt_double karto::KT_TOLERANCE = 1e-06
 
BasicEvent< LogMessageArguments > karto::LogMessage
 
T * karto::SmartPointer< T >::m_pPointer
 
const kt_objecttype karto::ObjectType_Camera = ObjectType_Sensor | 0x04
 
const kt_objecttype karto::ObjectType_CameraImage = ObjectType_SensorData | 0x40
 
const kt_objecttype karto::ObjectType_CustomItem = 0x00004000
 
const kt_objecttype karto::ObjectType_DatasetInfo = ObjectType_Object | 0x02
 
const kt_objecttype karto::ObjectType_DatasetObjectMessage = ObjectType_Message | 0x10
 
const kt_objecttype karto::ObjectType_DefaultCustomItem = ObjectType_CustomItem | 0x01
 
const kt_objecttype karto::ObjectType_DoubleMessage = ObjectType_Message | 0x04
 
const kt_objecttype karto::ObjectType_Drive = ObjectType_Sensor | 0x01
 
const kt_objecttype karto::ObjectType_DrivePose = ObjectType_SensorData | 0x01
 
const kt_objecttype karto::ObjectType_Grid = 0x00008000
 
const kt_objecttype karto::ObjectType_Header = ObjectType_Misc | 0x01
 
const kt_objecttype karto::ObjectType_Image = ObjectType_Misc | 0x02
 
const kt_objecttype karto::ObjectType_Int32sMessage = ObjectType_Message | 0x01
 
const kt_objecttype karto::ObjectType_Int64sMessage = ObjectType_Message | 0x02
 
const kt_objecttype karto::ObjectType_LaserRangeFinder = ObjectType_Sensor | 0x02
 
const kt_objecttype karto::ObjectType_LaserRangeScan = ObjectType_SensorData | 0x02
 
const kt_objecttype karto::ObjectType_LocalizedLaserScan = ObjectType_SensorData | 0x20
 
const kt_objecttype karto::ObjectType_LocalizedObject = ObjectType_SensorData | 0x04
 
const kt_objecttype karto::ObjectType_LocalizedPointScan = ObjectType_SensorData | 0x10
 
const kt_objecttype karto::ObjectType_LocalizedRangeScan = ObjectType_SensorData | 0x08
 
const kt_objecttype karto::ObjectType_Message = 0x00010000
 
const kt_objecttype karto::ObjectType_Misc = 0x10000000
 
const kt_objecttype karto::ObjectType_Module = ObjectType_Object | 0x04
 
const kt_objecttype karto::ObjectType_ModuleParameters = ObjectType_Object | 0x01
 
const kt_objecttype karto::ObjectType_None = 0x00000000
 
const kt_objecttype karto::ObjectType_Object = 0x00020000
 
const kt_objecttype karto::ObjectType_OccupancyGrid = ObjectType_Grid | 0x01
 
const kt_objecttype karto::ObjectType_OccupancyGridTile = ObjectType_Grid | 0x02
 
const kt_objecttype karto::ObjectType_Rfid = ObjectType_CustomItem | 0x02
 
const kt_objecttype karto::ObjectType_ScansPoseUpdateMessage = ObjectType_Message | 0x20
 
const kt_objecttype karto::ObjectType_Sensor = 0x00001000
 
const kt_objecttype karto::ObjectType_SensorData = 0x00002000
 
const kt_objecttype karto::ObjectType_StringMessage = ObjectType_Message | 0x08
 
const kt_objecttype karto::ObjectType_TiledOccupancyGrid = ObjectType_Object | 0x08
 

Friends

template<class Other >
class karto::SmartPointer< T >::SmartPointer
 

Detailed Description

Macro Definition Documentation

#define const_forEach (   listtype,
  list 
)    for ( listtype::const_iterator iter = (list)->begin(); iter != (list)->end(); ++iter )

Iterate through items in const std::vector with iterator iter

Definition at line 100 of file Macros.h.

#define const_forEachAs (   listtype,
  list,
  iter 
)    for ( listtype::const_iterator iter = (list)->begin(); iter != (list)->end(); ++iter )

Iterate through items in const std::vector with provided iterator iter

Definition at line 106 of file Macros.h.

#define const_forEachR (   listtype,
  list 
)    for ( listtype::const_reverse_iterator iter = (list)->rbegin(); iter != (list)->rend(); ++iter )

Reverse iterate through items in const std::vector with iterator iter

Definition at line 118 of file Macros.h.

#define forEach (   listtype,
  list 
)    for ( listtype::iterator iter = (list)->begin(); iter != (list)->end(); ++iter )

Iterate through items in std::vector with iterator iter

Definition at line 88 of file Macros.h.

#define forEachAs (   listtype,
  list,
  iter 
)    for ( listtype::iterator iter = (list)->begin(); iter != (list)->end(); ++iter )

Iterate through items in std::vector with provided iterator iter

Definition at line 94 of file Macros.h.

#define forEachR (   listtype,
  list 
)    for ( listtype::reverse_iterator iter = (list)->rbegin(); iter != (list)->rend(); ++iter )

Reverse iterate through items in std::vector with iterator iter

Definition at line 112 of file Macros.h.

#define KARTO_AUTO_TYPE (   type,
  registerFunc 
)
Value:
template <> struct KartoTypeId<type> \
{ \
static const char* Get(kt_bool checkRegister = true) \
{ \
if (checkRegister) \
CheckTypeRegistered(#type, registerFunc); \
return #type; \
} \
}; \
bool kt_bool
Definition: Types.h:145
void CheckTypeRegistered(const char *pName, void(*registerFunc)())
Definition: Meta.cpp:24

Macro for adding a C++ class to the Meta system with a registration function as a callback. The registration function will be call the first time the provided class is accessed.

Definition at line 180 of file Meta.h.

#define karto_const_forEach (   listtype,
  list 
)    for ( listtype::ConstIterator iter = (list)->GetConstIterator(); iter.HasNext(); iter.Next())

Iterate through items in const karto::List with iterator iter

Definition at line 136 of file Macros.h.

#define karto_const_forEachAs (   listtype,
  list,
  iter 
)    for ( listtype::ConstIterator iter = (list)->GetConstIterator(); iter.HasNext(); iter.Next())

Iterate through items in const karto::List with provided iterator iter

Definition at line 142 of file Macros.h.

#define KARTO_DEPRECATED

Karto defines for handling deprecated code

Definition at line 39 of file Macros.h.

#define KARTO_EXPORT

Karto defines for windows dynamic build

Definition at line 78 of file Macros.h.

#define KARTO_FORCEINLINE

Karto defines for forcing inline code

Definition at line 56 of file Macros.h.

#define karto_forEach (   listtype,
  list 
)    for ( listtype::Iterator iter = (list)->GetIterator(); iter.HasNext(); iter.Next())

Iterate through items in karto::List with iterator iter

Definition at line 124 of file Macros.h.

#define karto_forEachAs (   listtype,
  list,
  iter 
)    for ( listtype::Iterator iter = (list)->GetIterator(); iter.HasNext(); iter.Next())

Iterate through items in karto::List with provided iterator iter

Definition at line 130 of file Macros.h.

#define KARTO_RTTI ( )
Value:
public: virtual const char* GetKartoClassId() const {return GetKartoTypeIdTemplate(this);} \
private:

Macro for getting the right runtime type info.

Definition at line 198 of file Meta.h.

#define KARTO_TYPE (   type)
Value:
template <> struct KartoTypeId<type> \
{ \
static const char* Get(kt_bool = true) {return #type;} \
}; \
bool kt_bool
Definition: Types.h:145

////////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////////////

/** Macro for adding a C++ class to the Meta system.

Definition at line 170 of file Meta.h.

#define KARTO_TYPECHECKCAST (   __Name__)
Value:
inline kt_bool Is##__Name__(Object* pObject) \
{ \
return dynamic_cast<__Name__ *>(pObject) != NULL;\
}
bool kt_bool
Definition: Types.h:145

Karto object type check

Definition at line 41 of file Object.h.

Typedef Documentation

typedef SmartPointer<Dataset> karto::DatasetPtr

Type declaration of Dataset managed by SmartPointer

Definition at line 102 of file Dataset.h.

Type declaration of kt_double List

Definition at line 53 of file SensorData.h.

typedef List< EnumPair > karto::EnumPairList

Type declaration of EnumPair List

Definition at line 70 of file MetaEnum.h.

typedef bool kt_bool

Type declaration of boolean type

Definition at line 145 of file Types.h.

typedef char kt_char

Type declaration of char type

Definition at line 150 of file Types.h.

typedef double kt_double

Type declaration of double type

Definition at line 160 of file Types.h.

typedef float kt_float

Type declaration of float type

Definition at line 155 of file Types.h.

typedef int16_t kt_int16s

Type declaration of 16 bit integer type

Definition at line 96 of file Types.h.

typedef uint16_t kt_int16u

Type declaration of unsigned 16 bit integer type

Definition at line 101 of file Types.h.

typedef int32_t kt_int32s

Type declaration of 32 bit integer type

Definition at line 106 of file Types.h.

typedef uint32_t kt_int32u

Type declaration of unsigned 32 bit integer type

Definition at line 111 of file Types.h.

typedef signed long long kt_int64s

Type declaration of 64 bit integer type

Definition at line 127 of file Types.h.

typedef unsigned long long kt_int64u

Type declaration of unsigned 64 bit integer type

Definition at line 132 of file Types.h.

typedef int8_t kt_int8s

Type declaration of 8 bit integer type

Definition at line 86 of file Types.h.

typedef uint8_t kt_int8u

Type declaration of unsigned 8 bit integer type

Definition at line 91 of file Types.h.

Type declaration of karto object type

Definition at line 165 of file Types.h.

typedef std::size_t kt_size_t

Type declaration of size_t type

Definition at line 138 of file Types.h.

typedef kt_int64s kt_tick

Type declaration of karto hight resolution timer tick type

Definition at line 170 of file Types.h.

typedef SmartPointer<LaserRangeFinder> karto::LaserRangeFinderPtr

Type declaration of LaserRangeFinder managed by SmartPointer

Definition at line 462 of file Sensor.h.

typedef List<LocalizedLaserScanPtr> karto::LocalizedLaserScanList

Type declaration of LocalizedLaserScan List

Definition at line 790 of file SensorData.h.

typedef SmartPointer<LocalizedLaserScan> karto::LocalizedLaserScanPtr

Type declaration of LocalizedLaserScan managed by SmartPointer

Definition at line 785 of file SensorData.h.

typedef List<LocalizedObjectPtr> karto::LocalizedObjectList

Type declaration of LocalizedObject List

Definition at line 556 of file SensorData.h.

typedef SmartPointer<LocalizedObject> karto::LocalizedObjectPtr

Type declaration of LocalizedObject managed by SmartPointer

Definition at line 551 of file SensorData.h.

typedef List<ObjectPtr> karto::ObjectList

Type declaration of Object List

Definition at line 182 of file Object.h.

typedef SmartPointer<Object> karto::ObjectPtr

Type declaration of Object managed by SmartPointer

Definition at line 177 of file Object.h.

typedef SmartPointer<OccupancyGrid> karto::OccupancyGridPtr

Type declaration of OccupancyGrid managed by SmartPointer

Definition at line 253 of file OccupancyGrid.h.

typedef List<SmartPointer<AbstractParameter> > karto::ParameterList

Type declaration of AbstractParameter List

Definition at line 342 of file Parameter.h.

typedef SmartPointer<ParameterSet> karto::ParameterSetPtr

Type declaration of ParameterSet managed by SmartPointer

Definition at line 426 of file Parameter.h.

typedef List<Pose2> karto::Pose2List

Type declaration of Pose2 List

Definition at line 2396 of file Geometry.h.

Type declaration of range readings List

Definition at line 48 of file SensorData.h.

typedef List<SensorPtr> karto::SensorList

Type declaration of Sensor List

Definition at line 119 of file Sensor.h.

typedef SmartPointer<Sensor> karto::SensorPtr

Type declaration of Sensor managed by SmartPointer

Definition at line 114 of file Sensor.h.

typedef Vector2<kt_double> karto::Vector2d

Type declaration of kt_double Vector2 as Vector2d

Definition at line 610 of file Geometry.h.

typedef List<Vector2d> karto::Vector2dList

Type declaration of Vector2d List

Definition at line 35 of file Sensor.h.

typedef Vector2<kt_int32s> karto::Vector2i

Type declaration of kt_int32s Vector2 as Vector2i

Definition at line 600 of file Geometry.h.

typedef Vector2<kt_int32u> karto::Vector2iu

Type declaration of kt_int32u Vector2 as Vector2iu

Definition at line 605 of file Geometry.h.

Type declaration of kt_double Vector3 as Vector3d

Definition at line 1046 of file Geometry.h.

Type declaration of kt_int32s Vector3 as Vector3i

Definition at line 1036 of file Geometry.h.

Type declaration of kt_int32u Vector3 as Vector3iu

Definition at line 1041 of file Geometry.h.

typedef Vector4<kt_double> karto::Vector4d

Type declaration of double Vector4 as Vector4d

Definition at line 1280 of file Geometry.h.

typedef Vector4<kt_int32s> karto::Vector4i

Type declaration of kt_int32s Vector4 as Vector4i

Definition at line 1270 of file Geometry.h.

typedef Vector4<kt_int32u> karto::Vector4iu

Type declaration of kt_int32u Vector4 as Vector4iu

Definition at line 1275 of file Geometry.h.

Enumeration Type Documentation

Valid grid cell states

Enumerator
GridStates_Unknown 
GridStates_Occupied 
GridStates_Free 

Definition at line 39 of file OccupancyGrid.h.

Enumerated type for valid LaserRangeFinder types

Enumerator
LaserRangeFinder_Custom 
LaserRangeFinder_Sick_LMS100 
LaserRangeFinder_Sick_LMS200 
LaserRangeFinder_Sick_LMS291 
LaserRangeFinder_Hokuyo_UTM_30LX 
LaserRangeFinder_Hokuyo_URG_04LX 

Definition at line 193 of file Sensor.h.

Log levels

Enumerator
LOG_NONE 

Disable all logging

LOG_FATAL 

Fatal log level

LOG_ERROR 

Error log level

LOG_WARNING 

Warning log level

LOG_INFORMATION 

Information log level

LOG_DEBUG 

Debug log level

Definition at line 43 of file Logger.h.

Parameter flags used by the KartoViewer application to control the visibility and read/write access

Enumerator
ParameterFlag_Read 

Parameter readable

ParameterFlag_Write 

Parameter writeable

ParameterFlag_Hidden 

Parameter hidden

ParameterFlag_System 

System parameter

Definition at line 43 of file Parameter.h.

Function Documentation

template<class T >
T karto::math::AlignValue ( size_t  value,
size_t  alignValue = 8 
)
inline

Aligns a value to the alignValue. The alignValue should be the power of two (2, 4, 8, 16, 32 and so on)

Parameters
valuevalue
alignValuevalue to align to
Returns
aligned value

Definition at line 275 of file Math.h.

template<typename T >
T* karto::any_cast ( Any pAny)

Cast for extracting a value of a given type from an Any

Parameters
pAnyAny value to cast
Returns
a qualified pointer to the value content if successful, otherwise NULL is returned

Definition at line 206 of file Any.h.

template<typename T >
const T* karto::any_cast ( const Any pAny)
inline

Cast for extracting a const value of a given type from an const Any

Parameters
pAnyAny value to cast
Returns
a qualified pointer to the value content if successful, otherwise NULL is returned

Definition at line 217 of file Any.h.

template<typename T >
T karto::any_cast ( const Any rAny)
inline

Cast for extracting a reference value of a given type from an Any Throws an Karto::Exception if unable to cast reference

Parameters
rAnyAny value to cast
Returns
a copy of the value content if successful

Definition at line 229 of file Any.h.

template<typename T >
const T& karto::math::Clip ( const T &  n,
const T &  minValue,
const T &  maxValue 
)
inline

Clips a number to the specified minimum and maximum values.

Parameters
nnumber to be clipped
minValueminimum value
maxValuemaximum value
Returns
the clipped value

Definition at line 151 of file Math.h.

kt_double karto::math::DegreesToRadians ( kt_double  degrees)
inline

Converts degrees into radians

Parameters
degreesdegrees
Returns
radian equivalent of degrees

Definition at line 83 of file Math.h.

template<class TObj , class TArgs >
static Delegate<TObj, TArgs, true> karto::delegate ( TObj *  pObj,
void(TObj::*)(const void *, TArgs &)  NotifyMethod 
)
static

Definition at line 1048 of file Event.h.

template<class TObj , class TArgs >
static Delegate<TObj, TArgs, false> karto::delegate ( TObj *  pObj,
void(TObj::*)(TArgs &)  NotifyMethod 
)
static

Definition at line 1054 of file Event.h.

template<class TArgs >
static FunctionDelegate<TArgs, true, true> karto::delegate ( void(*)(const void *, TArgs &)  NotifyMethod)
static

Definition at line 1060 of file Event.h.

template<class TArgs >
static FunctionDelegate<TArgs, true, false> karto::delegate ( void(*)(void *, TArgs &)  NotifyMethod)
static

Definition at line 1066 of file Event.h.

template<class TArgs >
static FunctionDelegate<TArgs, false> karto::delegate ( void(*)(TArgs &)  NotifyMethod)
static

Definition at line 1072 of file Event.h.

kt_bool karto::math::DoubleEqual ( kt_double  a,
kt_double  b 
)
inline

Checks whether two numbers are equal within a certain tolerance.

Parameters
avalue
bvalue
Returns
true if a and b differ by at most a certain tolerance.

Definition at line 162 of file Math.h.

template<typename T >
static kt_bool karto::FromString ( const String rStringValue,
Vector3< T > &  rValue 
)
inlinestatic

Definition at line 3252 of file Geometry.h.

template<class T>
T* karto::SmartPointer< T >::Get ( ) const
inline

Gets the contained pointer

Returns
contained pointer

Definition at line 112 of file SmartPointer.h.

KARTO_EXPORT LogLevel karto::GetLogLevel ( )

Gets the log level

Returns
log level

Definition at line 178 of file Logger.cpp.

const MetaClass& karto::GetMetaClassByIndex ( kt_size_t  index)
inline

Gets a registered MetaClass by index. Use GetRegisteredMetaClassSize to get index range.

Parameters
index
Returns
reference to registered MetaClass
Exceptions
Exceptionif index is out of range

Definition at line 54 of file Meta.h.

const MetaClass& karto::GetMetaClassByName ( const karto::String rName)
inline

Gets a registered MetaClass by name.

Parameters
rNameClass name
Returns
reference to registered MetaClass
Exceptions
Exceptionif there is no registered MetaClass by specified name

Definition at line 65 of file Meta.h.

template<typename T >
const MetaClass& karto::GetMetaClassByObject ( const T &  rObject)

Gets a registered MetaClass by object.

Parameters
rObjectobject
Returns
reference to registered MetaClass
Exceptions
Exceptionif there is no registered MetaClass by object

Definition at line 77 of file Meta.h.

template<typename T >
const MetaClass& karto::GetMetaClassByType ( )

Gets a registered MetaClass by type.

Returns
reference to registered MetaClass
Exceptions
Exceptionif there is no registered MetaClass by type T

Definition at line 88 of file Meta.h.

const MetaEnum& karto::GetMetaEnumByIndex ( kt_size_t  index)
inline

Gets a registered MetaEnum by index. Use GetRegisteredMetaClassSize to get index range.

Parameters
index
Returns
reference to registered MetaEnum
Exceptions
Exceptionif index is out of range

Definition at line 112 of file Meta.h.

const MetaEnum& karto::GetMetaEnumByName ( const karto::String rName)
inline

Gets a registered MetaEnum by name.

Parameters
rNameenum name
Returns
reference to registered MetaEnum
Exceptions
Exceptionif there is no registered MetaEnum by specified name

Definition at line 123 of file Meta.h.

template<typename T >
const MetaEnum& karto::GetMetaEnumByObject ( const T &  rObject)

Gets a registered MetaEnum by object.

Parameters
rObjectobject
Returns
reference to registered MetaEnum
Exceptions
Exceptionif there is no registered MetaEnum by object

Definition at line 135 of file Meta.h.

template<typename T >
const MetaEnum& karto::GetMetaEnumByType ( )

Gets a registered MetaEnum by type.

Returns
reference to registered MetaEnum
Exceptions
Exceptionif there is no registered MetaEnum by type T

Definition at line 146 of file Meta.h.

kt_size_t karto::GetRegisteredMetaClassSize ( )
inline

Gets the number of MetaClass's registered.

Returns
number of MetClass's registered

Definition at line 43 of file Meta.h.

kt_size_t karto::GetRegisteredMetaEnumSize ( )
inline

Gets the number of MetaEnum's registered.

Returns
number of MetaEnum's registered

Definition at line 101 of file Meta.h.

template<typename T >
kt_bool karto::math::InRange ( const T &  value,
const T &  a,
const T &  b 
)
inline

/** Checks whether value is in the range [a;b]

Parameters
valuevalue
aa
bb
Returns
whether the given value is in the range [a;b]

Definition at line 203 of file Math.h.

kt_bool karto::IsLocalizedLaserScan ( Object pObject)
inline

Determines whether a given object is a laser scan object

Parameters
pObjectobject in question
Returns
whether the given object is a laser scan object

Definition at line 53 of file TypeCasts.h.

template<typename T >
kt_bool karto::math::IsUpTo ( const T &  value,
const T &  maximum 
)
inline

Checks whether value is in the range [0;maximum)

Parameters
valuevalue
maximummaximum
Returns
whether the given value is in the range [0;maximum)

Definition at line 175 of file Math.h.

template<class T>
kt_bool karto::SmartPointer< T >::IsValid ( ) const
inline

Whether the contained pointer is valid

Returns
true if the contained pointer is valid

Definition at line 121 of file SmartPointer.h.

karto::KARTO_AUTO_TYPE ( LaserRangeFinderType  ,
RegisterLaserRangeFinderType 
)

Auto register LaserRangeFinderType with MetaEnumManager

karto::KARTO_TYPE ( Sensor  )

Register Sensor with MetaClassManager

karto::KARTO_TYPE ( Object  )

Register Object with MetaClassManager

karto::KARTO_TYPE ( Drive  )

Register Drive with MetaClassManager

karto::KARTO_TYPE ( SensorData  )

Register SensorData with MetaClassManager

karto::KARTO_TYPE ( OccupancyGrid  )

Register OccupancyGrid with MetaClassManager

karto::KARTO_TYPE ( LaserRangeScan  )

Register LaserRangeScan with MetaClassManager

karto::KARTO_TYPE ( AbstractParameter  )

Register AbstractParameter with MetaClassManager

karto::KARTO_TYPE ( DrivePose  )

Register DrivePose with MetaClassManager

karto::KARTO_TYPE ( LaserRangeFinder  )

Register LaserRangeFinder with MetaClassManager

karto::KARTO_TYPE ( Grid< kt_int8u )

Register Grid<kt_int8u> with MetaClassManager

karto::KARTO_TYPE ( Grid< kt_int32u )

Register Grid<kt_int32u> with MetaClassManager

karto::KARTO_TYPE ( Grid< kt_float )

Register Grid<kt_float> with MetaClassManager

karto::KARTO_TYPE ( Grid< kt_double )

Register Grid<kt_double> with MetaClassManager

karto::KARTO_TYPE ( LocalizedObject  )

Register LocalizedObject with MetaClassManager

karto::KARTO_TYPE ( Parameter< kt_bool )

Register Parameter<kt_bool> with MetaClassManager

karto::KARTO_TYPE ( Parameter< kt_char )

Register Parameter<kt_char> with MetaClassManager

karto::KARTO_TYPE ( Parameter< kt_int8s )

Register Parameter<kt_int8s> with MetaClassManager

karto::KARTO_TYPE ( Parameter< kt_int8u )

Register Parameter<kt_int8u> with MetaClassManager

karto::KARTO_TYPE ( Parameter< kt_int16s )

Register Parameter<kt_int16s> with MetaClassManager

karto::KARTO_TYPE ( Parameter< kt_int16u )

Register Parameter<kt_int16u> with MetaClassManager

karto::KARTO_TYPE ( Parameter< kt_int32s )

Register Parameter<kt_int32s> with MetaClassManager

karto::KARTO_TYPE ( Parameter< kt_int32u )

Register Parameter<kt_int32u> with MetaClassManager

karto::KARTO_TYPE ( Parameter< kt_int64s )

Register Parameter<kt_int64s> with MetaClassManager

karto::KARTO_TYPE ( Parameter< kt_int64u )

Register Parameter<kt_int64u> with MetaClassManager

karto::KARTO_TYPE ( Parameter< kt_float )

Register Parameter<kt_float> with MetaClassManager

karto::KARTO_TYPE ( Parameter< kt_double )

Register Parameter<kt_double> with MetaClassManager

karto::KARTO_TYPE ( Parameter< karto::String )

Register Parameter<karto::String> with MetaClassManager

karto::KARTO_TYPE ( Parameter< karto::Size2< kt_int32s > >  )

Register Parameter<karto::Size2<kt_int32s> > with MetaClassManager

karto::KARTO_TYPE ( Parameter< karto::Size2< kt_int32u > >  )

Register Parameter<karto::Size2<kt_int32u> > with MetaClassManager

karto::KARTO_TYPE ( Parameter< karto::Size2< kt_double > >  )

Register Parameter<karto::Size2<kt_double> > with MetaClassManager

karto::KARTO_TYPE ( Parameter< karto::Vector2i )

Register Parameter<karto::Vector2i> with MetaClassManager

karto::KARTO_TYPE ( Parameter< karto::Vector3i )

Register Parameter<karto::Vector3i> with MetaClassManager

karto::KARTO_TYPE ( Parameter< karto::Vector4i )

Register Parameter<karto::Vector4i> with MetaClassManager

karto::KARTO_TYPE ( Parameter< karto::Vector2< kt_int32u > >  )

Register Parameter<karto::Vector2iu> with MetaClassManager

karto::KARTO_TYPE ( Parameter< karto::Vector3iu )

Register Parameter<karto::Vector3iu> with MetaClassManager

karto::KARTO_TYPE ( Parameter< karto::Vector4iu )

Register Parameter<karto::Vector4iu> with MetaClassManager

karto::KARTO_TYPE ( Parameter< karto::Vector2< kt_double > >  )

Register Parameter<karto::Vector2d> with MetaClassManager

karto::KARTO_TYPE ( Parameter< karto::Vector3d )

Register Parameter<karto::Vector3d> with MetaClassManager

karto::KARTO_TYPE ( Parameter< karto::Vector4d )

Register Parameter<karto::Vector4d> with MetaClassManager

karto::KARTO_TYPE ( Parameter< karto::Quaternion )

Register Parameter<karto::Quaternion> with MetaClassManager

karto::KARTO_TYPE ( Parameter< karto::Color )

Register Parameter<karto::Color> with MetaClassManager

karto::KARTO_TYPE ( Parameter< karto::Pose2 )

Register Parameter<karto::Pose2> with MetaClassManager

karto::KARTO_TYPE ( Parameter< karto::Pose3 )

Register Parameter<karto::Pose3> with MetaClassManager

karto::KARTO_TYPE ( Parameter< karto::gps::PointGps )

Register Parameter<karto::gps::PointGps> with MetaClassManager

karto::KARTO_TYPE ( LocalizedLaserScan  )

Register LocalizedLaserScan with MetaClassManager

karto::KARTO_TYPE ( ParameterEnum  )

Register ParameterEnum with MetaClassManager

karto::KARTO_TYPE ( LocalizedPointScan  )

Register LocalizedPointScan with MetaClassManager

karto::KARTO_TYPE ( LocalizedRangeScan  )

Register LocalizedRangeScan with MetaClassManager

KARTO_EXPORT void karto::Log ( LogLevel  level,
const karto::String rMessage 
)

Logs a message with the specified log level. Wrapper for Poco logging. Check if OpenKarto is compiled with POCO with USE_POCO=1.

Note
All releases of Karto from SRI International are compiled with POCO. If you are manually compiling OpenKarto and don't include POCO, logging is not functional!
Parameters
levellog level
rMessagemessage

Definition at line 183 of file Logger.cpp.

template<typename T >
const T& karto::math::Maximum ( const T &  value1,
const T &  value2 
)
inline

Binary maximum function

Parameters
value1value
value2value
Returns
the greater of value1 and value2

Definition at line 138 of file Math.h.

template<typename T >
const T& karto::math::Minimum ( const T &  value1,
const T &  value2 
)
inline

Binary minimum function

Parameters
value1value
value2value
Returns
the lesser of value1 and value2

Definition at line 126 of file Math.h.

kt_double karto::math::NormalizeAngle ( kt_double  angle)
inline

Normalizes angle to be in the range of [-pi, pi]

Parameters
angleto be normalized
Returns
normalized angle

Definition at line 213 of file Math.h.

kt_double karto::math::NormalizeAngleDifference ( kt_double  minuend,
kt_double  subtrahend 
)
inline

Returns an equivalent angle to the first parameter such that the difference when the second parameter is subtracted from this new value is an angle in the normalized range of [-pi, pi], i.e. abs(minuend - subtrahend) <= pi.

Parameters
minuendminuend
subtrahendsubtrahend
Returns
normalized angle

Definition at line 252 of file Math.h.

template<class T>
karto::SmartPointer< T >::operator T * ( ) const
inline

Gets the contained pointer

Returns
contained pointer

Definition at line 131 of file SmartPointer.h.

template<class T>
T& karto::SmartPointer< T >::operator* ( ) const
inline

Gets a reference to the contained pointer

Returns
reference to the contained pointer

Definition at line 140 of file SmartPointer.h.

template<class T>
T* karto::SmartPointer< T >::operator-> ( ) const
inline

Gets the contained pointer

Returns
contained pointer

Definition at line 149 of file SmartPointer.h.

template<class T>
SmartPointer& karto::SmartPointer< T >::operator= ( const SmartPointer< T > &  rOther)
inline

Assignment operator

Definition at line 157 of file SmartPointer.h.

template<class T>
SmartPointer& karto::SmartPointer< T >::operator= ( T *  pPointer)
inline

Assignment operator

Definition at line 183 of file SmartPointer.h.

template<class T>
template<class Other >
SmartPointer& karto::SmartPointer< T >::operator= ( const SmartPointer< Other > &  rOther)
inline

Assignment operator

Definition at line 209 of file SmartPointer.h.

kt_double karto::math::RadiansToDegrees ( kt_double  radians)
inline

Converts radians into degrees

Parameters
radiansradians
Returns
degree equivalent of radians

Definition at line 93 of file Math.h.

void karto::RegisterLaserRangeFinderType ( )

LaserRangeFinderType auto register callback function

Definition at line 34 of file Sensor.cpp.

template<class T>
void karto::SmartPointer< T >::Release ( )
inline

Sets pointer to NULL

Definition at line 98 of file SmartPointer.h.

kt_double karto::math::Round ( kt_double  value)
inline

Round function

Parameters
valuevalue
Returns
rounds value to the nearest whole number (as double)

Definition at line 114 of file Math.h.

KARTO_EXPORT void karto::SetLogLevel ( LogLevel  level)

Sets the log level

Parameters
levelnew log level

Definition at line 165 of file Logger.cpp.

template<class T>
karto::SmartPointer< T >::SmartPointer ( )
inline

Default constructor

Definition at line 45 of file SmartPointer.h.

template<class T>
karto::SmartPointer< T >::SmartPointer ( const SmartPointer< T > &  rOther)
inline

Copy constructor

Definition at line 53 of file SmartPointer.h.

template<class T>
template<class Other >
karto::SmartPointer< T >::SmartPointer ( const SmartPointer< Other > &  rOther)
inline

Copy constructor

Definition at line 65 of file SmartPointer.h.

template<class T>
karto::SmartPointer< T >::SmartPointer ( T *  pPointer)
inline

Assignment operator

Definition at line 77 of file SmartPointer.h.

template<typename T >
T karto::math::Square ( value)
inline

Square function

Parameters
valuevalue
Returns
square of value

Definition at line 104 of file Math.h.

template<class T >
void karto::math::Swap ( T &  x,
T &  y 
)
inline

Swaps the value of the given parameters

Parameters
xvalue
yvalue

Definition at line 286 of file Math.h.

template<typename T >
String karto::StringHelper::ToString ( const Size2< T > &  rValue)
inlinestatic

Converts the given size to a string

Parameters
rValuevalue to be converted
Returns
string representation of the size

Definition at line 3228 of file Geometry.h.

template<typename T >
String karto::StringHelper::ToString ( const Vector2< T > &  rValue)
inlinestatic

Converts the given vector to a string

Parameters
rValuevalue to be converted
Returns
string representation of the vector

Definition at line 3234 of file Geometry.h.

template<typename T >
String karto::StringHelper::ToString ( const Vector3< T > &  rValue)
inlinestatic

Converts the given vector to a string

Parameters
rValuevalue to be converted
Returns
string representation of the vector

Definition at line 3240 of file Geometry.h.

template<typename T >
String karto::StringHelper::ToString ( const Vector4< T > &  rValue)
inlinestatic

Converts the given vector to a string

Parameters
rValuevalue to be converted
Returns
string representation of the vector

Definition at line 3246 of file Geometry.h.

template<class T>
virtual karto::SmartPointer< T >::~SmartPointer ( )
inlinevirtual

Destructor

Definition at line 89 of file SmartPointer.h.

Variable Documentation

const kt_double karto::KT_180_PI = 57.29577951308232087685

180 / PI

Definition at line 63 of file Math.h.

const kt_double karto::KT_2PI = 6.28318530717958647692

2 * PI

Definition at line 48 of file Math.h.

const kt_double karto::KT_PI = 3.14159265358979323846

Platform independent pi definitions PI

Definition at line 43 of file Math.h.

const kt_double karto::KT_PI_180 = 0.01745329251994329577

PI / 180

Definition at line 58 of file Math.h.

const kt_double karto::KT_PI_2 = 1.57079632679489661923

PI / 2

Definition at line 53 of file Math.h.

const kt_double karto::KT_TOLERANCE = 1e-06

Karto tolerance level

Definition at line 71 of file Math.h.

KARTO_EXPORT BasicEvent< LogMessageArguments > karto::LogMessage

Log message event

Definition at line 44 of file Logger.cpp.

template<class T>
T* karto::SmartPointer< T >::m_pPointer
private

Definition at line 233 of file SmartPointer.h.

const kt_objecttype karto::ObjectType_Camera = ObjectType_Sensor | 0x04

Karto camera object type

Definition at line 241 of file Object.h.

const kt_objecttype karto::ObjectType_CameraImage = ObjectType_SensorData | 0x40

Karto camera image object type

Definition at line 286 of file Object.h.

const kt_objecttype karto::ObjectType_CustomItem = 0x00004000

Karto custom item object type

Definition at line 206 of file Object.h.

const kt_objecttype karto::ObjectType_DatasetInfo = ObjectType_Object | 0x02

Karto dataset info object type

Definition at line 316 of file Object.h.

const kt_objecttype karto::ObjectType_DatasetObjectMessage = ObjectType_Message | 0x10

Karto dataset object message object type

Definition at line 351 of file Object.h.

const kt_objecttype karto::ObjectType_DefaultCustomItem = ObjectType_CustomItem | 0x01

Karto default custom item object type

Definition at line 276 of file Object.h.

const kt_objecttype karto::ObjectType_DoubleMessage = ObjectType_Message | 0x04

Karto double message object type

Definition at line 341 of file Object.h.

const kt_objecttype karto::ObjectType_Drive = ObjectType_Sensor | 0x01

Karto drive object type

Definition at line 231 of file Object.h.

const kt_objecttype karto::ObjectType_DrivePose = ObjectType_SensorData | 0x01

Karto drive pose object type

Definition at line 246 of file Object.h.

const kt_objecttype karto::ObjectType_Grid = 0x00008000

Karto grid object type

Definition at line 211 of file Object.h.

const kt_objecttype karto::ObjectType_Header = ObjectType_Misc | 0x01

Karto header object type

Definition at line 301 of file Object.h.

const kt_objecttype karto::ObjectType_Image = ObjectType_Misc | 0x02

Karto header object type

Definition at line 306 of file Object.h.

const kt_objecttype karto::ObjectType_Int32sMessage = ObjectType_Message | 0x01

Karto int32s message object type

Definition at line 331 of file Object.h.

const kt_objecttype karto::ObjectType_Int64sMessage = ObjectType_Message | 0x02

Karto int64s message object type

Definition at line 336 of file Object.h.

const kt_objecttype karto::ObjectType_LaserRangeFinder = ObjectType_Sensor | 0x02

Karto laser range finder object type

Definition at line 236 of file Object.h.

const kt_objecttype karto::ObjectType_LaserRangeScan = ObjectType_SensorData | 0x02

Karto laser range scan object type

Definition at line 251 of file Object.h.

const kt_objecttype karto::ObjectType_LocalizedLaserScan = ObjectType_SensorData | 0x20

Karto localized laser scan object type

Definition at line 271 of file Object.h.

const kt_objecttype karto::ObjectType_LocalizedObject = ObjectType_SensorData | 0x04

Karto localized object object type

Definition at line 256 of file Object.h.

const kt_objecttype karto::ObjectType_LocalizedPointScan = ObjectType_SensorData | 0x10

Karto localized point scan object type

Definition at line 266 of file Object.h.

const kt_objecttype karto::ObjectType_LocalizedRangeScan = ObjectType_SensorData | 0x08

Karto localized range scan object type

Definition at line 261 of file Object.h.

const kt_objecttype karto::ObjectType_Message = 0x00010000

Karto message object type

Definition at line 216 of file Object.h.

const kt_objecttype karto::ObjectType_Misc = 0x10000000

Karto misc object type

Definition at line 226 of file Object.h.

const kt_objecttype karto::ObjectType_Module = ObjectType_Object | 0x04

Karto module object type

Definition at line 321 of file Object.h.

const kt_objecttype karto::ObjectType_ModuleParameters = ObjectType_Object | 0x01

Karto parameters object type

Definition at line 311 of file Object.h.

const kt_objecttype karto::ObjectType_None = 0x00000000

Karto object type

Definition at line 191 of file Object.h.

const kt_objecttype karto::ObjectType_Object = 0x00020000

Karto object object type

Definition at line 221 of file Object.h.

const kt_objecttype karto::ObjectType_OccupancyGrid = ObjectType_Grid | 0x01

Karto occupancy grid object type

Definition at line 291 of file Object.h.

const kt_objecttype karto::ObjectType_OccupancyGridTile = ObjectType_Grid | 0x02

Karto occupancy grid tile object type

Definition at line 296 of file Object.h.

const kt_objecttype karto::ObjectType_Rfid = ObjectType_CustomItem | 0x02

Karto rfid object type

Definition at line 281 of file Object.h.

const kt_objecttype karto::ObjectType_ScansPoseUpdateMessage = ObjectType_Message | 0x20

Karto scans pose update message object type

Definition at line 356 of file Object.h.

const kt_objecttype karto::ObjectType_Sensor = 0x00001000

Karto sensor object type

Definition at line 196 of file Object.h.

const kt_objecttype karto::ObjectType_SensorData = 0x00002000

Karto sensor data object type

Definition at line 201 of file Object.h.

const kt_objecttype karto::ObjectType_StringMessage = ObjectType_Message | 0x08

Karto string message object type

Definition at line 346 of file Object.h.

const kt_objecttype karto::ObjectType_TiledOccupancyGrid = ObjectType_Object | 0x08

Karto tiled occupancy grid object type

Definition at line 326 of file Object.h.

Friends

template<class T>
template<class Other >
friend class SmartPointer
friend

Definition at line 235 of file SmartPointer.h.



nav2d_karto
Author(s): Sebastian Kasperski
autogenerated on Thu Jun 6 2019 19:20:25