Main MRPT website > C++ reference for MRPT 1.9.9
Classes | Namespaces | Macros | Enumerations | Functions
[mrpt-obs]

Detailed Description

Back to list of all libraries | See all modules

Library mrpt-obs


In this library there are five key elements or groups of elements:

See the list of classes in mrpt::obs

Classes

class  mrpt::maps::CMetricMap
 Declares a virtual base class for all metric maps storage classes. More...
 
class  mrpt::maps::mrptEventMetricMapClear
 Event emitted by a metric up upon call of clear() More...
 
class  mrpt::maps::mrptEventMetricMapInsert
 Event emitted by a metric up upon a succesful call to insertObservation() More...
 
class  mrpt::maps::CSimpleMap
 This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be totally determined with this information. More...
 
struct  mrpt::maps::TMetricMapInitializer
 Virtual base for specifying the kind and parameters of one map (normally, to be inserted into mrpt::maps::CMultiMetricMap) See mrpt::maps::TSetOfMetricMapInitializers::loadFromConfigFile() as an easy way of initialize this object, or construct with the factory methods <metric_map_class>::MapDefinition() and TMetricMapInitializer::factory() More...
 
class  mrpt::maps::TSetOfMetricMapInitializers
 A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap See the comments for TSetOfMetricMapInitializers::loadFromConfigFile, and "CMultiMetricMap::setListOfMaps" for effectively creating the list of desired maps. More...
 
class  mrpt::obs::CAction
 Declares a class for storing a robot action. More...
 
class  mrpt::obs::CActionCollection
 Declares a class for storing a collection of robot actions. More...
 
class  mrpt::obs::CActionRobotMovement2D
 Represents a probabilistic 2D movement of the robot mobile base. More...
 
class  mrpt::obs::CActionRobotMovement3D
 Represents a probabilistic 3D (6D) movement. More...
 
class  mrpt::obs::CObservation
 Declares a class that represents any robot's observation. More...
 
class  mrpt::obs::CObservation2DRangeScan
 A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser scanner). More...
 
class  mrpt::obs::CObservation3DRangeScan
 Declares a class derived from "CObservation" that encapsules a 3D range scan measurement, as from a time-of-flight range camera or any other RGBD sensor. More...
 
class  mrpt::obs::CObservation6DFeatures
 An observation of one or more "features" or "objects", possibly identified with a unique ID, whose relative SE(3) pose is observed with respect to the sensor. More...
 
class  mrpt::obs::CObservationBatteryState
 This represents a measurement of the batteries on the robot. More...
 
class  mrpt::obs::CObservationBeaconRanges
 Declares a class derived from "CObservation" that represents one (or more) range measurements to labeled beacons. More...
 
class  mrpt::obs::CObservationBearingRange
 This observation represents a number of range-bearing value pairs, each one for a detected landmark, which optionally can have identification IDs. More...
 
class  mrpt::obs::CObservationCANBusJ1939
 This class stores a message from a CAN BUS with the protocol J1939. More...
 
class  mrpt::obs::CObservationComment
 This "observation" is actually a placeholder for a text block with comments or additional parameters attached to a given rawlog file. More...
 
class  mrpt::obs::CObservationGasSensors
 Declares a class derived from "CObservation" that represents a set of readings from gas sensors. More...
 
class  mrpt::obs::CObservationGPS
 This class stores messages from GNSS or GNSS+IMU devices, from consumer-grade inexpensive GPS receivers to Novatel/Topcon/... More...
 
class  mrpt::obs::CObservationImage
 Declares a class derived from "CObservation" that encapsules an image from a camera, whose relative pose to robot is also stored. More...
 
class  mrpt::obs::CObservationIMU
 This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation, raw gyroscope and accelerometer values), altimeters or magnetometers. More...
 
class  mrpt::obs::CObservationOdometry
 An observation of the current (cumulative) odometry for a wheeled robot. More...
 
class  mrpt::obs::CObservationRange
 Declares a class derived from "CObservation" that encapsules a single range measurement, and associated parameters. More...
 
class  mrpt::obs::CObservationRawDAQ
 Store raw data from a Data Acquisition (DAQ) device, such that input or output analog and digital channels, counters from encoders, etc. More...
 
class  mrpt::obs::CObservationReflectivity
 Declares a class derived from "CObservation" that encapsules a single short-range reflectivity measurement. More...
 
class  mrpt::obs::CObservationRFID
 This represents one or more RFID tags observed by a receiver. More...
 
class  mrpt::obs::CObservationRGBD360
 Declares a class derived from "CObservation" that encapsules an omnidirectional RGBD measurement from a set of RGBD sensors. More...
 
class  mrpt::obs::CObservationRobotPose
 An observation providing an alternative robot pose from an external source. More...
 
class  mrpt::obs::CObservationSkeleton
 This class stores a skeleton as tracked by OPENNI2 & NITE2 libraries from PrimeSense sensors. More...
 
class  mrpt::obs::CObservationStereoImages
 Observation class for either a pair of left+right or left+disparity images from a stereo camera. More...
 
class  mrpt::obs::CObservationStereoImagesFeatures
 Declares a class derived from "CObservation" that encapsules a pair of cameras and a set of matched image features extracted from them. More...
 
class  mrpt::obs::CObservationVelodyneScan
 A CObservation-derived class for RAW DATA (and optionally, point cloud) of scans from 3D Velodyne LIDAR scanners. More...
 
class  mrpt::obs::CObservationWindSensor
 Declares a class derived from "CObservation" that represents the wind measurements taken on the robot by an anemometer. More...
 
class  mrpt::obs::CObservationWirelessPower
 This represents a measurement of the wireless strength perceived by the robot. More...
 
class  mrpt::obs::CRawlog
 This class stores a rawlog (robotic datasets) in one of two possible formats: More...
 
class  mrpt::obs::CSensoryFrame
 Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximately at the same time as one "snapshot" of the environment. More...
 
class  mrpt::obs::CSinCosLookUpTableFor2DScans
 A smart look-up-table (LUT) of sin/cos values for 2D laser scans. More...
 
struct  mrpt::obs::T2DScanProperties
 Auxiliary struct that holds all the relevant geometry information about a 2D scan. More...
 
struct  mrpt::obs::VelodyneCalibration
 Velodyne calibration data, for usage in mrpt::obs::CObservationVelodyneScan. More...
 

Namespaces

 mrpt::obs
 This namespace contains representation of robot actions and observations.
 

Macros

#define INVALID_BEACON_ID   (-1)
 Used for CObservationBeaconRange, CBeacon, etc. More...
 
#define INVALID_LANDMARK_ID   (-1)
 Used for CObservationBearingRange::TMeasurement::beaconID and others. More...
 

Enumerations

enum  mrpt::obs::TIMUDataIndex {
  mrpt::obs::IMU_X_ACC = 0, mrpt::obs::IMU_Y_ACC, mrpt::obs::IMU_Z_ACC, mrpt::obs::IMU_YAW_VEL,
  mrpt::obs::IMU_PITCH_VEL, mrpt::obs::IMU_ROLL_VEL, mrpt::obs::IMU_X_VEL, mrpt::obs::IMU_Y_VEL,
  mrpt::obs::IMU_Z_VEL, mrpt::obs::IMU_YAW, mrpt::obs::IMU_PITCH, mrpt::obs::IMU_ROLL,
  mrpt::obs::IMU_X, mrpt::obs::IMU_Y, mrpt::obs::IMU_Z, mrpt::obs::IMU_MAG_X,
  mrpt::obs::IMU_MAG_Y, mrpt::obs::IMU_MAG_Z, mrpt::obs::IMU_PRESSURE, mrpt::obs::IMU_ALTITUDE,
  mrpt::obs::IMU_TEMPERATURE, mrpt::obs::IMU_ORI_QUAT_X, mrpt::obs::IMU_ORI_QUAT_Y, mrpt::obs::IMU_ORI_QUAT_Z,
  mrpt::obs::IMU_ORI_QUAT_W, mrpt::obs::IMU_YAW_VEL_GLOBAL, mrpt::obs::IMU_PITCH_VEL_GLOBAL, mrpt::obs::IMU_ROLL_VEL_GLOBAL,
  mrpt::obs::IMU_X_ACC_GLOBAL, mrpt::obs::IMU_Y_ACC_GLOBAL, mrpt::obs::IMU_Z_ACC_GLOBAL, mrpt::obs::COUNT_IMU_DATA_FIELDS
}
 Symbolic names for the indices of IMU data (refer to mrpt::obs::CObservationIMU) More...
 

Functions

bool mrpt::obs::carmen_log_parse_line (std::istream &in_stream, std::vector< mrpt::obs::CObservation::Ptr > &out_imported_observations, const mrpt::system::TTimeStamp &time_start_log)
 Parse one line from an text input stream and interpret it as a CARMEN log entry, returning its MRPT observation representation. More...
 
template<class OBSERVATION_T >
OBSERVATION_T::Ptr mrpt::obs::utils::getObservation (mrpt::obs::CSensoryFrame::Ptr &observations, mrpt::obs::CObservation::Ptr &observation, bool priority_to_sf=true)
 Given an mrpt::obs::CSensoryFrame and a mrpt::obs::CObservation pointer if a OBSERVATION_T type observation is included and return a pointer to that instance. More...
 

Macro Definition Documentation

◆ INVALID_BEACON_ID

#define INVALID_BEACON_ID   (-1)

Used for CObservationBeaconRange, CBeacon, etc.

Definition at line 24 of file CObservation.h.

◆ INVALID_LANDMARK_ID

#define INVALID_LANDMARK_ID   (-1)

Used for CObservationBearingRange::TMeasurement::beaconID and others.

Definition at line 27 of file CObservation.h.

Enumeration Type Documentation

◆ TIMUDataIndex

Symbolic names for the indices of IMU data (refer to mrpt::obs::CObservationIMU)

Enumerator
IMU_X_ACC 

x-axis acceleration (local/vehicle frame) (m/sec2)

IMU_Y_ACC 

y-axis acceleration (local/vehicle frame) (m/sec2)

IMU_Z_ACC 

z-axis acceleration (local/vehicle frame) (m/sec2)

IMU_YAW_VEL 

yaw angular velocity (local/vehicle frame) (rad/sec)

IMU_PITCH_VEL 

pitch angular velocity (local/vehicle frame) (rad/sec)

IMU_ROLL_VEL 

roll angular velocity (local/vehicle frame) (rad/sec)

IMU_X_VEL 

x-axis velocity (global/navigation frame) (m/sec)

IMU_Y_VEL 

y-axis velocity (global/navigation frame) (m/sec)

IMU_Z_VEL 

z-axis velocity (global/navigation frame) (m/sec)

IMU_YAW 

orientation yaw absolute value (global/navigation frame) (rad)

IMU_PITCH 

orientation pitch absolute value (global/navigation frame) (rad)

IMU_ROLL 

orientation roll absolute value (global/navigation frame) (rad)

IMU_X 

x absolute value (global/navigation frame) (meters)

IMU_Y 

y absolute value (global/navigation frame) (meters)

IMU_Z 

z absolute value (global/navigation frame) (meters)

IMU_MAG_X 

x magnetic field value (local/vehicle frame) (gauss)

IMU_MAG_Y 

y magnetic field value (local/vehicle frame) (gauss)

IMU_MAG_Z 

z magnetic field value (local/vehicle frame) (gauss)

IMU_PRESSURE 

air pressure (Pascals)

IMU_ALTITUDE 

altitude from an altimeter (meters)

IMU_TEMPERATURE 

temperature (degrees Celsius)

IMU_ORI_QUAT_X 

Orientation Quaternion X (global/navigation frame)

IMU_ORI_QUAT_Y 

Orientation Quaternion Y (global/navigation frame)

IMU_ORI_QUAT_Z 

Orientation Quaternion Z (global/navigation frame)

IMU_ORI_QUAT_W 

Orientation Quaternion W (global/navigation frame)

IMU_YAW_VEL_GLOBAL 

yaw angular velocity (global/navigation frame) (rad/sec)

IMU_PITCH_VEL_GLOBAL 

pitch angular velocity (global/navigation frame) (rad/sec)

IMU_ROLL_VEL_GLOBAL 

roll angular velocity (global/navigation frame) (rad/sec)

IMU_X_ACC_GLOBAL 

x-axis acceleration (global/navigation frame) (m/sec2)

IMU_Y_ACC_GLOBAL 

y-axis acceleration (global/navigation frame) (m/sec2)

IMU_Z_ACC_GLOBAL 

z-axis acceleration (global/navigation frame) (m/sec2)

COUNT_IMU_DATA_FIELDS 

Definition at line 26 of file CObservationIMU.h.

Function Documentation

◆ carmen_log_parse_line()

bool mrpt::obs::carmen_log_parse_line ( std::istream &  in_stream,
std::vector< mrpt::obs::CObservation::Ptr > &  out_imported_observations,
const mrpt::system::TTimeStamp time_start_log 
)

Parse one line from an text input stream and interpret it as a CARMEN log entry, returning its MRPT observation representation.

The first word in each line determines the type of that entry. Supported line entries in this class are the following:

Note that the sensor position on the robot will be always deduced from the corresponding CARMEN log line automatically.

The following entry types will be IGNORED, since with the tags above will be enough in most applications.

  • "ODOM"
  • "RAWLASER"

About the PARAM entries: This functions has an internal static status consisting on some PARAM values which have effects on the future read observations. When the function finds one of these, it stores the parameter value, return an empty vector of observations, and use those values for future laser entries of types FLASER or RLASER. Currently, only these parameters are processed:

  • "robot_front_laser_max"
  • "laser_front_laser_resolution"
  • "robot_rear_laser_max"
  • "laser_rear_laser_resolution"
Parameters
time_start_logThe real timestamp that corresponds to a "0" in the CARMEN log (you can get a mrpt::system::now() once and pass that same value with each call).

References: http://carmen.sourceforge.net/doc/binary__loggerplayback.html

Returns
true on success, false on end-of-file (EOF).
Exceptions
std::runtime_errorOn any invalid line found.

Definition at line 27 of file carmen_log_tools.cpp.

References mrpt::obs::CObservation2DRangeScan::aperture, mrpt::DEG2RAD(), mrpt::system::lowerCase(), mrpt::obs::CObservation2DRangeScan::maxRange, mrpt::math::TPose2D::phi, mrpt::obs::CObservation2DRangeScan::resizeScan(), mrpt::obs::CObservation2DRangeScan::scan, mrpt::system::secondsToTimestamp(), mrpt::obs::CObservation::sensorLabel, mrpt::obs::CObservation2DRangeScan::sensorPose, mrpt::obs::CObservation2DRangeScan::setScanRange(), mrpt::obs::CObservation2DRangeScan::setScanRangeValidity(), mrpt::system::strStartsI(), THROW_EXCEPTION_FMT, mrpt::obs::CObservation::timestamp, trim(), val, mrpt::math::TPose2D::x, and mrpt::math::TPose2D::y.

◆ getObservation()

template<class OBSERVATION_T >
OBSERVATION_T::Ptr mrpt::obs::utils::getObservation ( mrpt::obs::CSensoryFrame::Ptr observations,
mrpt::obs::CObservation::Ptr observation,
bool  priority_to_sf = true 
)

Given an mrpt::obs::CSensoryFrame and a mrpt::obs::CObservation pointer if a OBSERVATION_T type observation is included and return a pointer to that instance.

Note
Pointer to a single instance is going to be returned. If a suitable observation exists in both the CSensoryFrame and CObservation the outcome is decided by the priority_to_sf flag
Returns
Pointer to the observation of the given type. Otherwise, an empty Ptr object is returned if a valid observation is not found.

Definition at line 36 of file obs_utils.h.

Referenced by mrpt::hwdrivers::CWirelessPower::doProcess(), mrpt::hwdrivers::CImpinjRFID::doProcess(), mrpt::hwdrivers::CBoardSonars::doProcess(), mrpt::hwdrivers::CEnoseModular::doProcess(), mrpt::hwdrivers::CBoardENoses::doProcess(), and mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::doProcess().




Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST