Class RosRobotLocalizationListener
Defined in File ros_robot_localization_listener.hpp
Class Documentation
-
class RosRobotLocalizationListener
RosRobotLocalizationListener class.
This class wraps the RobotLocalizationEstimator. It listens to topics over which the (filtered) robot state is published (odom and accel) and pushes them into its instance of the RobotLocalizationEstimator. It exposes a getState method to offer the user the estimated state at a requested time. This class offers the option to run this listener without the need to run a separate node. If you do wish to run this functionality in a separate node, consider the robot localization listener node.
Public Functions
Constructor.
The RosRobotLocalizationListener constructor initializes nodehandles, subscribers, a filter for synchronized listening to the topics it subscribes to, and an instance of the RobotLocalizationEstimator.
- Parameters:
node – [in] - rclcpp node shared pointer
-
~RosRobotLocalizationListener()
Destructor.
Empty destructor
-
bool getState(const double time, const std::string &frame_id, Eigen::VectorXd &state, Eigen::MatrixXd &covariance, std::string world_frame_id = "") const
Get a state from the localization estimator.
Requests the predicted state and covariance at a given time from the Robot Localization Estimator.
- Parameters:
time – [in] - time of the requested state
frame_id – [in] - frame id of which the state is requested.
state – [out] - state at the requested time
covariance – [out] - covariance at the requested time
- Returns:
false if buffer is empty, true otherwise
-
bool getState(const rclcpp::Time &rclcpp_time, const std::string &frame_id, Eigen::VectorXd &state, Eigen::MatrixXd &covariance, const std::string &world_frame_id = "") const
Get a state from the localization estimator.
Overload of getState method for using ros::Time.
- Parameters:
rclcpp_time – [in] - ros time of the requested state
frame_id – [in] - frame id of which the state is requested.
state – [out] - state at the requested time
covariance – [out] - covariance at the requested time
- Returns:
false if buffer is empty, true otherwise
-
const std::string &getBaseFrameId() const
getBaseFrameId Returns the base frame id of the localization listener
- Returns:
The base frame id
-
const std::string &getWorldFrameId() const
getWorldFrameId Returns the world frame id of the localization listener
- Returns:
The world frame id