Structure used for storing and comparing measurements (for priority queues) More...
#include <filter_base.h>
Public Member Functions | |
Measurement () | |
bool | operator() (const boost::shared_ptr< Measurement > &a, const boost::shared_ptr< Measurement > &b) |
bool | operator() (const Measurement &a, const Measurement &b) |
Public Attributes | |
Eigen::MatrixXd | covariance_ |
Eigen::VectorXd | latestControl_ |
double | latestControlTime_ |
double | mahalanobisThresh_ |
Eigen::VectorXd | measurement_ |
double | time_ |
std::string | topicName_ |
std::vector< int > | updateVector_ |
Structure used for storing and comparing measurements (for priority queues)
Measurement units are assumed to be in meters and radians. Times are real-valued and measured in seconds.
Definition at line 61 of file filter_base.h.
|
inline |
Definition at line 101 of file filter_base.h.
|
inline |
Definition at line 91 of file filter_base.h.
|
inline |
Definition at line 96 of file filter_base.h.
Eigen::MatrixXd RobotLocalization::Measurement::covariance_ |
Definition at line 70 of file filter_base.h.
Eigen::VectorXd RobotLocalization::Measurement::latestControl_ |
Definition at line 85 of file filter_base.h.
double RobotLocalization::Measurement::latestControlTime_ |
Definition at line 88 of file filter_base.h.
double RobotLocalization::Measurement::mahalanobisThresh_ |
Definition at line 82 of file filter_base.h.
Eigen::VectorXd RobotLocalization::Measurement::measurement_ |
Definition at line 69 of file filter_base.h.
double RobotLocalization::Measurement::time_ |
Definition at line 79 of file filter_base.h.
std::string RobotLocalization::Measurement::topicName_ |
Definition at line 66 of file filter_base.h.
std::vector<int> RobotLocalization::Measurement::updateVector_ |
Definition at line 75 of file filter_base.h.