OKVIS ROS
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
Public Member Functions | Public Attributes | List of all members
okvis::Measurement< MEASUREMENT_T > Struct Template Reference

Generic measurements. More...

#include <Measurements.hpp>

Public Member Functions

 Measurement ()
 Default constructor. More...
 
 Measurement (const okvis::Time &timeStamp_, const MEASUREMENT_T &measurement_, int sensorId=-1)
 Constructor. More...
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW
okvis::Time 
timeStamp
 Measurement timestamp. More...
 
MEASUREMENT_T measurement
 Actual measurement. More...
 
int sensorId = -1
 Sensor ID. E.g. camera index in a multicamera setup. More...
 

Detailed Description

template<class MEASUREMENT_T>
struct okvis::Measurement< MEASUREMENT_T >

Generic measurements.

They always come with a timestamp such that we can perform any kind of asynchronous operation.

Template Parameters
MEASUREMENT_TMeasurement data type.

Constructor & Destructor Documentation

template<class MEASUREMENT_T >
okvis::Measurement< MEASUREMENT_T >::Measurement ( )
inline

Default constructor.

template<class MEASUREMENT_T >
okvis::Measurement< MEASUREMENT_T >::Measurement ( const okvis::Time timeStamp_,
const MEASUREMENT_T &  measurement_,
int  sensorId = -1 
)
inline

Constructor.

Parameters
timeStamp_Measurement timestamp.
measurement_Actual measurement.
sensorIdSensor ID (optional).

Member Data Documentation

template<class MEASUREMENT_T >
MEASUREMENT_T okvis::Measurement< MEASUREMENT_T >::measurement

Actual measurement.

template<class MEASUREMENT_T >
int okvis::Measurement< MEASUREMENT_T >::sensorId = -1

Sensor ID. E.g. camera index in a multicamera setup.

template<class MEASUREMENT_T >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW okvis::Time okvis::Measurement< MEASUREMENT_T >::timeStamp

Measurement timestamp.


The documentation for this struct was generated from the following file: