Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Refactoring: Splitting periodicUpdate method into smaller methods #761

Open
wants to merge 3 commits into
base: humble-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
34 changes: 26 additions & 8 deletions include/robot_localization/ros_filter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -196,17 +196,14 @@ class RosFilter : public rclcpp::Node
}

//! @brief Retrieves the EKF's output for broadcasting
//! @param[out] message - The standard ROS odometry message to be filled
//! @return true if the filter is initialized, false otherwise
//! @return The standard ROS odometry message if the filter is initialized, null otherwise
//!
bool getFilteredOdometryMessage(nav_msgs::msg::Odometry * message);
std::optional<nav_msgs::msg::Odometry> getFilteredOdometryMessage();

//! @brief Retrieves the EKF's acceleration output for broadcasting
//! @param[out] message - The standard ROS acceleration message to be filled
//! @return true if the filter is initialized, false otherwise
//! @return The standard ROS acceleration message if the filter is initialized, null otherwise
//!
bool getFilteredAccelMessage(
geometry_msgs::msg::AccelWithCovarianceStamped * message);
std::optional<geometry_msgs::msg::AccelWithCovarianceStamped> getFilteredAccelMessage();

//! @brief Callback method for receiving all IMU messages
//! @param[in] msg - The ROS IMU message to take in.
Expand Down Expand Up @@ -245,6 +242,27 @@ class RosFilter : public rclcpp::Node
//!
void periodicUpdate();

//! @brief Update filter with data from measurements queue.
//! @param[in] time - The time at which to carry out integration.
//!
void updateFilterWithMeasurements(const rclcpp::Time & time);

//! @brief publish world to base link transform and position with odometry message.
//! @param[in] filtered_position - filtered position from getFilteredOdometryMessage.
//! @return true if data is corrected otherwise false.
//!
bool publishPositionWithOdometry(const nav_msgs::msg::Odometry & filtered_position);

//! @brief Update world to base link transform using filtered position.
//! @param[in] filtered_position - filtered position from getFilteredOdometryMessage.
//!
void updateWorldToBaseLinkTransform(const nav_msgs::msg::Odometry & filtered_position);

//! @brief Publish world transform using frame id from filtered position.
//! @param[in] filtered_position - filtered position from getFilteredOdometryMessage.
//!
void publishWorldTransform(const nav_msgs::msg::Odometry & filtered_position);

//! @brief Callback method for receiving all odometry messages
//! @param[in] msg - The ROS odometry message to take in.
//! @param[in] topic_name - The topic name for the odometry message (only used
Expand Down Expand Up @@ -319,7 +337,7 @@ class RosFilter : public rclcpp::Node
//! @param[out] message - The standard ROS odometry message to be validated
//! @return true if the filter output is valid, false otherwise
//!
bool validateFilterOutput(nav_msgs::msg::Odometry * message);
bool validateFilterOutput(const nav_msgs::msg::Odometry & message);

protected:
//! @brief Finds the latest filter state before the given timestamp and makes
Expand Down
Loading