mars_lib  0.1.0.3dc76ee85e09
Modular and Robust Sensor-Fusion
Classes | Typedefs | Enumerations | Functions
mars Namespace Reference

Classes

class  Buffer
 BufferClass that holds mars::BufferEntryType elements and provides access methods. More...
 
class  CoreLogic
 The CoreLogic class represents the high-level logic for the operation of the filter. More...
 
class  CoreState
 
class  filesystem
 The filesystem class implements a wrapper for file or directory interaction. More...
 
class  ReadBarometerData
 
class  ReadCsv
 
class  ReadGpsData
 
class  ReadGpsWithVelData
 
class  ReadImuData
 
class  ReadMagData
 
class  ReadPoseData
 
class  ReadPositionData
 
class  ReadSimData
 
class  ReadVelocityData
 
class  ReadVisionData
 
class  WriteCsv
 
class  Chi2
 
class  Ekf
 
class  ProgressIndicator
 
class  Utils
 
class  MPerfType
 The MPerfType class Class of performance entry types. More...
 
class  MPerf
 The MPerf class Class which hosts individual time tracking instances. More...
 
class  NearestCov
 The NearestCov class generates a PSD Cov for a given pseudo-cov matrix. More...
 
class  SensorManager
 
struct  Attitude
 The Attitude struct. More...
 
class  AttitudeMeasurementType
 
class  AttitudeSensorClass
 
class  AttitudeSensorStateType
 
class  BindSensorData
 The BaseSensorData class binds the sensor state and covariance matrix. More...
 
class  BodyvelMeasurementType
 
class  BodyvelSensorClass
 
class  BodyvelSensorStateType
 
class  EmptyMeasurementType
 
class  EmptySensorClass
 
class  EmptySensorStateType
 
struct  GpsCoordinates
 The GpsCoordinates struct. More...
 
class  GpsConversion
 The GpsConversion class. More...
 
class  GpsMeasurementType
 
class  GpsSensorClass
 
class  GpsSensorStateType
 
class  GPSInit
 The GPSInit class is an initializer for calculating the average coordinates over a given time window. More...
 
class  GpsVelMeasurementType
 
class  GpsVelSensorClass
 
class  GpsVelSensorStateType
 
class  IMUMeasurementType
 
class  ImuSensorClass
 
class  MagMeasurementType
 
class  MagSensorClass
 
class  MagSensorStateType
 
class  MagnetometerInit
 
class  BaseMeas
 
class  MeasInterface
 
class  PoseMeasurementType
 
class  PoseSensorClass
 
class  PoseSensorStateType
 
class  PositionMeasurementType
 
class  PositionSensorClass
 
class  PositionSensorStateType
 
struct  Pressure
 The Pressure struct describes the raw pressure measurement used for conversion later. More...
 
struct  MediumPressureOptions
 The MediumPressureOptions struct contains all medium-related (gas, liquid, fluid, etc.) variables needed for pressure calculation. More...
 
class  PressureConversion
 
class  PressureMeasurementType
 
class  PressureSensorClass
 
class  PressureSensorStateType
 
class  PressureInit
 Pressure initalization object to calcualte mean initial pressure. More...
 
class  SensorAbsClass
 
class  SensorInterface
 
class  UpdateSensorAbsClass
 
class  VelocityMeasurementType
 
class  VelocitySensorClass
 
class  VelocitySensorStateType
 
class  VisionMeasurementType
 
class  VisionSensorClass
 
class  VisionSensorStateType
 
class  Time
 
class  BaseStates
 The BaseStates class is used to ensure that all sensor data classes define a covariance size for the 'bind_sensor_data' class. More...
 
class  BufferDataType
 The BufferDataType binds the core and sensor state in form of a shared void pointer. More...
 
class  BufferEntryType
 
class  CoreStateType
 
class  CoreType
 
class  Pose
 

Typedefs

using CsvDataType = std::map< std::string, std::vector< double > >
 
using HeaderMapType = std::map< int, std::string >
 
using NearestCovMethod = NearestCovMethods::NearestCovMethod
 
using AttitudeSensorData = BindSensorData< AttitudeSensorStateType >
 
using BodyvelSensorData = BindSensorData< BodyvelSensorStateType >
 
using EmptySensorData = BindSensorData< EmptySensorStateType >
 
using GpsSensorData = BindSensorData< GpsSensorStateType >
 
using GpsVelSensorData = BindSensorData< GpsVelSensorStateType >
 
using MagSensorData = BindSensorData< MagSensorStateType >
 
using PoseSensorData = BindSensorData< PoseSensorStateType >
 
using PositionSensorData = BindSensorData< PositionSensorStateType >
 
using PressureSensorData = BindSensorData< PressureSensorStateType >
 
using VelocitySensorData = BindSensorData< VelocitySensorStateType >
 
using VisionSensorData = BindSensorData< VisionSensorStateType >
 
using BufferMetadataType = BufferMetadataTypes::BufferMetadataType
 
using CoreStateMatrix = Eigen::Matrix< double, CoreStateType::size_error_, CoreStateType::size_error_ >
 
using CoreStateVector = Eigen::Matrix< double, CoreStateType::size_error_, 1 >
 

Enumerations

enum class  AttitudeSensorType { RP_TYPE , RPY_TYPE }
 

Functions

std::ostream & operator<< (std::ostream &os, AttitudeSensorType type)
 

Typedef Documentation

◆ CsvDataType

using mars::CsvDataType = typedef std::map<std::string, std::vector<double> >

◆ HeaderMapType

using mars::HeaderMapType = typedef std::map<int, std::string>

◆ NearestCovMethod

◆ AttitudeSensorData

◆ BodyvelSensorData

◆ EmptySensorData

◆ GpsSensorData

◆ GpsVelSensorData

◆ MagSensorData

◆ PoseSensorData

◆ PositionSensorData

◆ PressureSensorData

◆ VelocitySensorData

◆ VisionSensorData

◆ BufferMetadataType

◆ CoreStateMatrix

◆ CoreStateVector

using mars::CoreStateVector = typedef Eigen::Matrix<double, CoreStateType::size_error_, 1>

Enumeration Type Documentation

◆ AttitudeSensorType

Enumerator
RP_TYPE 

aviation attitude, roll and pitch only

RPY_TYPE 

full orientation, roll, pitch, and yaw

37 {
38  RP_TYPE,
39  RPY_TYPE,
40 };
@ RPY_TYPE
full orientation, roll, pitch, and yaw
@ RP_TYPE
aviation attitude, roll and pitch only

Function Documentation

◆ operator<<()

std::ostream& mars::operator<< ( std::ostream &  os,
AttitudeSensorType  type 
)
inline
43 {
44  switch (type)
45  {
46  case AttitudeSensorType::RP_TYPE:
47  os << "ROLL/PITCH";
48  break;
49  case AttitudeSensorType::RPY_TYPE:
50  os << "ROLL/PITCH/YAW";
51  break;
52  default:
53  os << "UNKNOWN";
54  break;
55  }
56  return os;
57 }