Class NavStateFilter

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public mrpt::system::COutputLogger

Class Documentation

class NavStateFilter : public mrpt::system::COutputLogger

Unified API for kinematic state filtering algorithms, fusing information from multiple odometry or twist sources.

Public Functions

NavStateFilter()
~NavStateFilter()
virtual void reset() = 0

Resets the estimator state to an initial state

virtual void initialize(const mrpt::containers::yaml &cfg) = 0

Initializes the object and reads all parameters from a YAML node.

Parameters:

cfg – a YAML node with a dictionary of parameters to load from.

virtual void fuse_pose(const mrpt::Clock::time_point &timestamp, const mrpt::poses::CPose3DPDFGaussian &pose, const std::string &frame_id) = 0

Integrates new SE(3) pose estimation of the vehicle wrt frame_id

virtual void fuse_odometry(const mrpt::obs::CObservationOdometry &odom, const std::string &odomName = "odom_wheels") = 0

Integrates new wheels-based odometry observations into the estimator. This is a convenience method that internally ends up calling fuse_pose(), but computing the uncertainty of odometry increments according to a given motion model.

virtual void fuse_imu(const mrpt::obs::CObservationIMU &imu) = 0

Integrates new IMU observations into the estimator

virtual void fuse_gnss(const mrpt::obs::CObservationGPS &gps) = 0

Integrates new GNSS observations into the estimator

virtual void fuse_twist(const mrpt::Clock::time_point &timestamp, const mrpt::math::TTwist3D &twist, const mrpt::math::CMatrixDouble66 &twistCov) = 0

Integrates new twist estimation (in the odom frame)

virtual std::optional<NavState> estimated_navstate(const mrpt::Clock::time_point &timestamp, const std::string &frame_id) = 0

Computes the estimated vehicle state at a given timestep using the observations in the time window. A std::nullopt is returned if there is no valid observations yet, or if requested a timestamp out of the model validity time window (e.g. too far in the future to be trustful).

inline void set_georeferencing_params(mrpt::topography::TGeodeticCoords geo_coord, mrpt::poses::CPose3DPDFGaussian T_enu_to_map)

Must be invoked with the mp2p_icp metric map geo-referencing information of the map in order to have GNSS observations correctly fused.

Parameters:
  • geo_coord – The geodetic coordinates (on WGS-84) of the metric map ENU frame of reference.

  • T_enu_to_map – The SE(3) transformation from the ENU (earth-north-up) frame to the metric map local frame of reference. If this is the identity (default) it means the map is already in ENU coordinates (i.e. +X is East, +Y is North, +Z is up) and the point (0,0,0) is the one having the geodetic coordinates geo_coord

Protected Attributes

std::optional<GeoReferenceParams> geoRefParams_
struct GeoReferenceParams

Public Members

mrpt::topography::TGeodeticCoords geo_coord
mrpt::poses::CPose3DPDFGaussian T_enu_to_map