Class RobotLocalizationEstimator
Defined in File robot_localization_estimator.hpp
Class Documentation
-
class RobotLocalizationEstimator
Robot Localization Listener class.
The Robot Localization Estimator class buffers states of and inputs to a system and can interpolate and extrapolate based on a given system model.
Public Functions
-
explicit RobotLocalizationEstimator(unsigned int buffer_capacity, FilterTypes::FilterType filter_type, const Eigen::MatrixXd &process_noise_covariance, const std::vector<double> &filter_args = std::vector<double>())
Constructor for the RobotLocalizationListener class.
- Parameters:
args – [in] - Generic argument container (not used here, but needed so that the ROS filters can pass arbitrary arguments to templated filter types).
-
virtual ~RobotLocalizationEstimator()
Destructor for the RobotLocalizationListener class.
-
void setState(const EstimatorState &state)
Sets the current internal state of the listener.
- Parameters:
state – [in] - The new state vector to set the internal state to
-
EstimatorResults::EstimatorResult getState(const double time, EstimatorState &state) const
Returns the state at a given time.
Projects the current state and error matrices forward using a model of the robot’s motion.
- Parameters:
time – [in] - The time to which the prediction is being made
state – [out] - The returned state at the given time
- Returns:
GetStateResult enum
-
void clearBuffer()
Clears the internal state buffer.
-
void setBufferCapacity(const int capacity)
Sets the buffer capacity.
- Parameters:
capacity – [in] - The new buffer capacity
-
unsigned int getBufferCapacity() const
Returns the buffer capacity.
Returns the number of EstimatorState objects that can be pushed to the buffer before old ones are dropped. (The capacity of the buffer).
- Returns:
buffer capacity
-
unsigned int getSize() const
Returns the current buffer size.
Returns the number of EstimatorState objects currently in the buffer.
- Returns:
current buffer size
-
explicit RobotLocalizationEstimator(unsigned int buffer_capacity, FilterTypes::FilterType filter_type, const Eigen::MatrixXd &process_noise_covariance, const std::vector<double> &filter_args = std::vector<double>())