Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
karto Namespace Reference

Namespaces

 math
 

Classes

class  AbstractParameter
 
class  BoundingBox2
 
class  BreadthFirstTraversal
 
class  CellUpdater
 
class  CoordinateConverter
 
class  CorrelationGrid
 
class  CustomData
 
class  Dataset
 
class  DatasetInfo
 
class  Drive
 
class  DrivePose
 
class  Edge
 
class  EdgeLabel
 
class  Exception
 
class  Functor
 
class  Graph
 
class  GraphTraversal
 
class  Grid
 
class  GridIndexLookup
 
class  LaserRangeFinder
 
class  LaserRangeScan
 
class  LinkInfo
 
struct  LocalizationScanVertex
 
class  LocalizedRangeScan
 
class  LocalizedRangeScanWithPoints
 
class  LookupArray
 
class  Mapper
 
class  MapperDebugListener
 
class  MapperGraph
 
class  MapperListener
 
class  MapperLoopClosureListener
 
class  MapperSensorManager
 
class  Matrix
 
class  Matrix3
 
class  Module
 
class  Name
 
class  NearPoseVisitor
 
class  NearScanVisitor
 
class  NonCopyable
 
class  Object
 
class  OccupancyGrid
 
class  Parameter
 
class  ParameterEnum
 
class  ParameterManager
 
class  Parameters
 
class  Pose2
 
class  Pose3
 
class  Quaternion
 
class  Rectangle2
 
class  ScanManager
 
class  ScanMatcher
 
class  ScanSolver
 
class  Sensor
 
class  SensorData
 
class  SensorManager
 
class  Singleton
 
class  Size2
 
class  Transform
 
class  Vector2
 
class  Vector3
 
class  Vertex
 
class  Visitor
 

Typedefs

typedef std::vector< CustomData * > CustomDataVector
 
typedef std::map< kt_int32s, Object * > DataMap
 
typedef std::queue< LocalizationScanVertexLocalizationScanVertices
 
typedef std::map< int, LocalizedRangeScan * > LocalizedRangeScanMap
 
typedef std::vector< LocalizedRangeScan * > LocalizedRangeScanVector
 
typedef std::vector< Object * > ObjectVector
 
typedef std::vector< AbstractParameter * > ParameterVector
 
typedef std::vector< Vector2< kt_double > > PointVectorDouble
 
typedef std::vector< Pose2Pose2Vector
 
typedef std::vector< kt_doubleRangeReadingsVector
 
typedef std::map< Name, Sensor * > SensorManagerMap
 
typedef std::vector< Sensor * > SensorVector
 

Enumerations

enum  GridStates { GridStates_Unknown = 0, GridStates_Occupied = 100, GridStates_Free = 255 }
 
enum  LaserRangeFinderType {
  LaserRangeFinder_Custom = 0, LaserRangeFinder_Sick_LMS100 = 1, LaserRangeFinder_Sick_LMS200 = 2, LaserRangeFinder_Sick_LMS291 = 3,
  LaserRangeFinder_Hokuyo_UTM_30LX = 4, LaserRangeFinder_Hokuyo_URG_04LX = 5
}
 

Functions

kt_bool IsDatasetInfo (Object *pObject)
 
kt_bool IsLaserRangeFinder (Object *pObject)
 
kt_bool IsLocalizedRangeScan (Object *pObject)
 
kt_bool IsLocalizedRangeScanWithPoints (Object *pObject)
 
kt_bool IsParameters (Object *pObject)
 
kt_bool IsSensor (Object *pObject)
 
kt_bool IsSensorData (Object *pObject)
 
std::ostream & operator<< (std::ostream &rStream, Exception &rException)
 

Variables

const kt_int32s INVALID_SCAN = std::numeric_limits<kt_int32s>::max()
 
const kt_double KT_180_PI = 57.29577951308232087685
 
const kt_double KT_2PI = 6.28318530717958647692
 
const kt_double KT_PI = 3.14159265358979323846
 
const kt_double KT_PI_180 = 0.01745329251994329577
 
const kt_double KT_PI_2 = 1.57079632679489661923
 
const kt_double KT_TOLERANCE = 1e-06
 

Typedef Documentation

◆ CustomDataVector

typedef std::vector<CustomData*> karto::CustomDataVector

Type declaration of CustomData vector

Definition at line 5116 of file Karto.h.

◆ DataMap

typedef std::map<kt_int32s, Object*> karto::DataMap

Definition at line 735 of file Karto.h.

◆ LocalizationScanVertices

Definition at line 1926 of file Mapper.h.

◆ LocalizedRangeScanMap

Definition at line 5880 of file Karto.h.

◆ LocalizedRangeScanVector

Type declaration of LocalizedRangeScan vector

Definition at line 5879 of file Karto.h.

◆ ObjectVector

typedef std::vector<Object*> karto::ObjectVector

Type declaration of Object vector

Definition at line 734 of file Karto.h.

◆ ParameterVector

Type declaration of AbstractParameter vector

Definition at line 279 of file Karto.h.

◆ PointVectorDouble

typedef std::vector< Vector2<kt_double> > karto::PointVectorDouble

Type declaration of Vector2<kt_double> vector

Definition at line 1283 of file Karto.h.

◆ Pose2Vector

typedef std::vector< Pose2 > karto::Pose2Vector

Type declaration of Pose2 vector

Definition at line 2271 of file Karto.h.

◆ RangeReadingsVector

typedef std::vector<kt_double> karto::RangeReadingsVector

Type declaration of range readings vector

Definition at line 5283 of file Karto.h.

◆ SensorManagerMap

typedef std::map<Name, Sensor*> karto::SensorManagerMap

Type declaration of <Name, Sensor*> map

Definition at line 3696 of file Karto.h.

◆ SensorVector

typedef std::vector<Sensor*> karto::SensorVector

Type declaration of Sensor vector

Definition at line 3687 of file Karto.h.

Enumeration Type Documentation

◆ GridStates

Enumerated type for valid grid cell states

Enumerator
GridStates_Unknown 
GridStates_Occupied 
GridStates_Free 

Definition at line 4444 of file Karto.h.

◆ LaserRangeFinderType

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 3084 of file Karto.h.

Function Documentation

◆ IsDatasetInfo()

kt_bool karto::IsDatasetInfo ( Object pObject)
inline

Whether the object is a DatasetInfo object

Parameters
pObjectobject
Returns
whether the object is a DatasetInfo object

Definition at line 806 of file Karto.h.

◆ IsLaserRangeFinder()

kt_bool karto::IsLaserRangeFinder ( Object pObject)
inline

Whether the object is a laser range finder

Parameters
pObjectobject
Returns
whether the object is a laser range finder

Definition at line 766 of file Karto.h.

◆ IsLocalizedRangeScan()

kt_bool karto::IsLocalizedRangeScan ( Object pObject)
inline

Whether the object is a localized range scan

Parameters
pObjectobject
Returns
whether the object is a localized range scan

Definition at line 776 of file Karto.h.

◆ IsLocalizedRangeScanWithPoints()

kt_bool karto::IsLocalizedRangeScanWithPoints ( Object pObject)
inline

Whether the object is a localized range scan with points

Parameters
pObjectobject
Returns
whether the object is a localized range scan with points

Definition at line 786 of file Karto.h.

◆ IsParameters()

kt_bool karto::IsParameters ( Object pObject)
inline

Whether the object is a Parameters object

Parameters
pObjectobject
Returns
whether the object is a Parameters object

Definition at line 796 of file Karto.h.

◆ IsSensor()

kt_bool karto::IsSensor ( Object pObject)
inline

Whether the object is a sensor

Parameters
pObjectobject
Returns
whether the object is a sensor

Definition at line 746 of file Karto.h.

◆ IsSensorData()

kt_bool karto::IsSensorData ( Object pObject)
inline

Whether the object is sensor data

Parameters
pObjectobject
Returns
whether the object is sensor data

Definition at line 756 of file Karto.h.

◆ operator<<()

std::ostream& karto::operator<< ( std::ostream &  rStream,
Exception rException 
)

Write exception to output stream

Parameters
rStreamoutput stream
rExceptionexception to write

Definition at line 151 of file Karto.cpp.

Variable Documentation

◆ INVALID_SCAN

const kt_int32s karto::INVALID_SCAN = std::numeric_limits<kt_int32s>::max()

Lets define max value of kt_int32s (int32_t) to use it to mark invalid scans

Definition at line 47 of file Math.h.

◆ KT_180_PI

const kt_double karto::KT_180_PI = 57.29577951308232087685

Definition at line 36 of file Math.h.

◆ KT_2PI

const kt_double karto::KT_2PI = 6.28318530717958647692

Definition at line 33 of file Math.h.

◆ KT_PI

const kt_double karto::KT_PI = 3.14159265358979323846

Platform independent pi definitions

Definition at line 32 of file Math.h.

◆ KT_PI_180

const kt_double karto::KT_PI_180 = 0.01745329251994329577

Definition at line 35 of file Math.h.

◆ KT_PI_2

const kt_double karto::KT_PI_2 = 1.57079632679489661923

Definition at line 34 of file Math.h.

◆ KT_TOLERANCE

const kt_double karto::KT_TOLERANCE = 1e-06

Lets define a small number!

Definition at line 41 of file Math.h.



slam_toolbox
Author(s): Steve Macenski
autogenerated on Thu Jan 11 2024 03:37:56