Namespaces | |
karto::gps | |
karto::math | |
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_double > | karto::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_double > | karto::RangeReadingsList |
typedef List< SensorPtr > | karto::SensorList |
typedef SmartPointer< Sensor > | karto::SensorPtr |
typedef Vector2< kt_double > | karto::Vector2d |
typedef List< Vector2d > | karto::Vector2dList |
typedef Vector2< kt_int32s > | karto::Vector2i |
typedef Vector2< kt_int32u > | karto::Vector2iu |
typedef Vector3< kt_double > | karto::Vector3d |
typedef Vector3< kt_int32s > | karto::Vector3i |
typedef Vector3< kt_int32u > | karto::Vector3iu |
typedef Vector4< kt_double > | karto::Vector4d |
typedef Vector4< kt_int32s > | karto::Vector4i |
typedef Vector4< kt_int32u > | karto::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 > | |
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 > | |
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 > | |
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 () |
Friends | |
template<class Other > | |
class | karto::SmartPointer< T >::SmartPointer |
#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 | |||
) |
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.
#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
#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
#define KARTO_DEPRECATED |
#define KARTO_EXPORT |
#define KARTO_FORCEINLINE |
#define karto_forEach | ( | listtype, | |
list | |||
) | for ( listtype::Iterator iter = (list)->GetIterator(); iter.HasNext(); iter.Next()) |
Iterate through items in karto::List with iterator iter
#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
#define KARTO_RTTI | ( | ) |
#define KARTO_TYPE | ( | type | ) |
////////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////////////
/** Macro for adding a C++ class to the Meta system.
#define KARTO_TYPECHECKCAST | ( | __Name__ | ) |
Karto object type check
typedef SmartPointer<Dataset> karto::DatasetPtr |
Type declaration of Dataset managed by SmartPointer
typedef List<kt_double> karto::DoubleList |
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 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 SmartPointer<LaserRangeFinder> karto::LaserRangeFinderPtr |
Type declaration of LaserRangeFinder managed by SmartPointer
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 |
typedef SmartPointer<Object> karto::ObjectPtr |
Type declaration of Object managed by SmartPointer
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.
typedef List<kt_double> karto::RangeReadingsList |
Type declaration of range readings List
Definition at line 48 of file SensorData.h.
typedef List<SensorPtr> karto::SensorList |
typedef SmartPointer<Sensor> karto::SensorPtr |
Type declaration of Sensor managed by SmartPointer
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 |
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.
typedef Vector3<kt_double> karto::Vector3d |
Type declaration of kt_double Vector3 as Vector3d
Definition at line 1046 of file Geometry.h.
typedef Vector3<kt_int32s> karto::Vector3i |
Type declaration of kt_int32s Vector3 as Vector3i
Definition at line 1036 of file Geometry.h.
typedef Vector3<kt_int32u> karto::Vector3iu |
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.
enum karto::GridStates |
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 |
enum karto::LogLevel |
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.
|
inline |
T* karto::any_cast | ( | Any * | pAny | ) |
|
inline |
|
inline |
|
inline |
|
static |
|
static |
|
static |
|
static |
|
static |
|
inlinestatic |
Definition at line 3252 of file Geometry.h.
|
inline |
KARTO_EXPORT LogLevel karto::GetLogLevel | ( | ) |
|
inline |
|
inline |
const MetaClass& karto::GetMetaClassByObject | ( | const T & | rObject | ) |
const MetaClass& karto::GetMetaClassByType | ( | ) |
|
inline |
|
inline |
const MetaEnum& karto::GetMetaEnumByObject | ( | const T & | rObject | ) |
const MetaEnum& karto::GetMetaEnumByType | ( | ) |
|
inline |
|
inline |
|
inline |
Determines whether a given object is a laser scan object
pObject | object in question |
Definition at line 53 of file TypeCasts.h.
|
inline |
|
inline |
Whether 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 | ( | 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 | ( | LaserRangeFinder | ) |
Register LaserRangeFinder with MetaClassManager
Register Grid<kt_int8u> with MetaClassManager
Register Grid<kt_int32u> with MetaClassManager
Register Grid<kt_double> with MetaClassManager
karto::KARTO_TYPE | ( | LocalizedObject | ) |
Register LocalizedObject with MetaClassManager
Register Parameter<kt_bool> with MetaClassManager
Register Parameter<kt_int32u> with MetaClassManager
Register Parameter<kt_int64s> with MetaClassManager
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.
level | log level |
rMessage | message |
Definition at line 183 of file Logger.cpp.
|
inline |
|
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.
minuend | minuend |
subtrahend | subtrahend |
|
inline |
|
inline |
Gets a reference to the contained pointer
Definition at line 140 of file SmartPointer.h.
|
inline |
|
inline |
Assignment operator
Definition at line 157 of file SmartPointer.h.
|
inline |
Assignment operator
Definition at line 183 of file SmartPointer.h.
|
inline |
Assignment operator
Definition at line 209 of file SmartPointer.h.
void karto::RegisterLaserRangeFinderType | ( | ) |
LaserRangeFinderType auto register callback function
Definition at line 34 of file Sensor.cpp.
|
inline |
Sets pointer to NULL
Definition at line 98 of file SmartPointer.h.
KARTO_EXPORT void karto::SetLogLevel | ( | LogLevel | level | ) |
|
inline |
Default constructor
Definition at line 45 of file SmartPointer.h.
|
inline |
Copy constructor
Definition at line 53 of file SmartPointer.h.
|
inline |
Copy constructor
Definition at line 65 of file SmartPointer.h.
|
inline |
Assignment operator
Definition at line 77 of file SmartPointer.h.
|
inline |
|
inline |
|
inlinestatic |
Converts the given size to a string
rValue | value to be converted |
Definition at line 3228 of file Geometry.h.
|
inlinestatic |
Converts the given vector to a string
rValue | value to be converted |
Definition at line 3234 of file Geometry.h.
|
inlinestatic |
Converts the given vector to a string
rValue | value to be converted |
Definition at line 3240 of file Geometry.h.
|
inlinestatic |
Converts the given vector to a string
rValue | value to be converted |
Definition at line 3246 of file Geometry.h.
|
inlinevirtual |
Destructor
Definition at line 89 of file SmartPointer.h.
const kt_double karto::KT_180_PI = 57.29577951308232087685 |
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 |
KARTO_EXPORT BasicEvent< LogMessageArguments > karto::LogMessage |
Log message event
Definition at line 44 of file Logger.cpp.
|
private |
Definition at line 233 of file SmartPointer.h.
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 |
|
friend |
Definition at line 235 of file SmartPointer.h.