Classes |
class | GPSConversion |
class | CheckFuzzyTracking |
class | CheckFuzzyTracking< EKFState_T, mpl_::void_ > |
class | MSF_Core |
| The core class of the EKF Does propagation of state and covariance but also applying measurements and managing states and measurements in lists sorted by time stamp. More...
|
class | IMUHandler |
class | IMUHandler_ROS |
class | MSF_MeasurementBase |
| The base class for all measurement types. These are the objects provided to the EKF core to be applied in correct order to the states. More...
|
class | MSF_InvalidMeasurement |
| An invalid measurement needed for the measurement container to report if something went wrong. More...
|
class | MSF_Measurement |
| The class for sensor based measurements which we want to apply to a state in the update routine of the EKF. This calls the apply correction method of the EKF core. More...
|
class | MSF_InitMeasurement |
| A measurement to be send to initialize parts of or the full EKF state this can especially be used to split the initialization of the EKF between multiple sensors which init different parts of the state. More...
|
class | sortMeasurements |
| A comparator to sort measurements by time. More...
|
class | SensorHandler |
| Handles a sensor driver which provides the sensor readings. More...
|
class | MSF_SensorManager |
| A manager for a given sensor set. Handlers for individual sensors (camera/vicon etc.) are registered with this class as handlers of particular sensors. This class also owns the EKF core instance and handles the initialization of the filter. More...
|
class | MSF_SensorManagerROS |
| Abstract class defining user configurable calculations for the msf_core with ROS interfaces. More...
|
class | SortedContainer |
| Manages a sorted container with strict less than ordering used to store state and measurement objects which can then be queried for closest states/measurements to a given time instant. More...
|
struct | StateVar_T |
| A state variable with a name as specified in the state name enum. More...
|
struct | GenericState_T |
| The state vector containing all the state variables for this EKF configuration. More...
|
class | sortStates |
| Comparator for the state objects. sorts by time asc. More...
|
class | StateVisitor |
| Visitor pattern to allow the user to set state init values. More...
|
Functions |
double | timehuman (double val) |
template<typename D > |
Eigen::MatrixBase< D >::Scalar | getMedian (const Eigen::MatrixBase< D > &data) |
Vector3 | geometry_msgsToEigen (const geometry_msgs::Point &p) |
| Converts a geometry_msgs::Point to an Eigen Vector3d.
|
Eigen::Quaterniond | geometry_msgsToEigen (const geometry_msgs::Quaternion &q) |
| Converts a geometry_msgs::Quaternion to an Eigen::Quaterniond.
|
Matrix3 | geometry_msgsCovBlockToEigen (const geometry_msgs::PoseWithCovariance::_covariance_type &gcov, int start_row, int start_col) |
| Returns a 3x3 covariance block entry from a geometry_msgs::PoseWithCovariance::covariance array.
|
template<class Derived > |
void | eigenCovBlockToGeometry_msgs (geometry_msgs::PoseWithCovariance::_covariance_type &gcov, const Eigen::MatrixBase< Derived > &ecov, int start_row, int start_col) |
| Fills a 3x3 covariance block entry of a geometry_msgs::PoseWithCovariance::covariance array from an Eigen 3x3 matrix.
|
template<class Derived > |
geometry_msgs::Point | eigenToGeometry_msgs (const Eigen::MatrixBase< Derived > &p) |
| Converts any eigen vector with 3 elements to a geometry_msgs::Point.
|
geometry_msgs::Quaternion | eigenToGeometry_msgs (const Eigen::Quaterniond &q) |
| Converts an Eigen::Quaterniond to a geometry_msgs::Quaternion.
|