karto Namespace Reference

Namespaces

namespace  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
class  LocalizedRangeScan
class  LookupArray
class  Mapper
class  MapperDebugListener
class  MapperGraph
class  MapperListener
class  MapperLoopClosureListener
class  MapperSensorManager
class  Matrix
class  Matrix3
class  Module
class  Name
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::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 IsParameters (Object *pObject)
kt_bool IsSensor (Object *pObject)
kt_bool IsSensorData (Object *pObject)
std::ostream & operator<< (std::ostream &rStream, Exception &rException)

Variables

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

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

Definition at line 4591 of file Karto.h.

Definition at line 5209 of file Karto.h.

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

Definition at line 637 of file Karto.h.

Typedef for vectors of Parameter

Definition at line 225 of file Karto.h.

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

Typedef for vectors of points

Definition at line 1139 of file Karto.h.

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

Typedef for vectors of Pose2

Definition at line 2063 of file Karto.h.

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

Definition at line 4735 of file Karto.h.

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

Definition at line 3355 of file Karto.h.

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

Definition at line 3349 of file Karto.h.


Enumeration Type Documentation

Enumerated type for valid grid cell states

Enumerator:
GridStates_Unknown 
GridStates_Occupied 
GridStates_Free 

Definition at line 3995 of file Karto.h.

Enumerator:
LaserRangeFinder_Custom 
LaserRangeFinder_Sick_LMS100 
LaserRangeFinder_Sick_LMS200 
LaserRangeFinder_Sick_LMS291 
LaserRangeFinder_Hokuyo_UTM_30LX 
LaserRangeFinder_Hokuyo_URG_04LX 

Definition at line 2841 of file Karto.h.


Function Documentation

kt_bool karto::IsDatasetInfo ( Object *  pObject  )  [inline]

Whether the object is a DatasetInfo object

Parameters:
pObject object
Returns:
whether the object is a DatasetInfo object

Definition at line 698 of file Karto.h.

kt_bool karto::IsLaserRangeFinder ( Object *  pObject  )  [inline]

Whether the object is a laser range finder

Parameters:
pObject object
Returns:
whether the object is a laser range finder

Definition at line 668 of file Karto.h.

kt_bool karto::IsLocalizedRangeScan ( Object *  pObject  )  [inline]

Whether the object is a localized range scan

Parameters:
pObject object
Returns:
whether the object is a localized range scan

Definition at line 678 of file Karto.h.

kt_bool karto::IsParameters ( Object *  pObject  )  [inline]

Whether the object is a Parameters object

Parameters:
pObject object
Returns:
whether the object is a Parameters object

Definition at line 688 of file Karto.h.

kt_bool karto::IsSensor ( Object *  pObject  )  [inline]

Whether the object is a sensor

Parameters:
pObject object
Returns:
whether the object is a sensor

Definition at line 648 of file Karto.h.

kt_bool karto::IsSensorData ( Object *  pObject  )  [inline]

Whether the object is sensor data

Parameters:
pObject object
Returns:
whether the object is sensor data

Definition at line 658 of file Karto.h.

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

Write exception to output stream

Parameters:
rStream output stream
rException exception to write

Definition at line 129 of file Karto.cpp.


Variable Documentation

const kt_double karto::KT_180_PI = 57.29577951308232087685

Definition at line 35 of file Math.h.

const kt_double karto::KT_2PI = 6.28318530717958647692

Definition at line 32 of file Math.h.

const kt_double karto::KT_PI = 3.14159265358979323846

Platform independent pi definitions

Definition at line 31 of file Math.h.

const kt_double karto::KT_PI_180 = 0.01745329251994329577

Definition at line 34 of file Math.h.

const kt_double karto::KT_PI_2 = 1.57079632679489661923

Definition at line 33 of file Math.h.

Lets define a small number!

Definition at line 40 of file Math.h.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


karto
Author(s): SRI International (package maintained by Brian Gerkey)
autogenerated on Fri Jan 11 10:07:05 2013