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

move updating measurements into new method #746

Closed
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
5 changes: 5 additions & 0 deletions include/robot_localization/ros_filter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -353,6 +353,11 @@ class RosFilter : public rclcpp::Node
//!
void clearMeasurementQueue();

//! @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 Adds a diagnostic message to the accumulating map and updates the
//! error level
//! @param[in] error_level - The error level of the diagnostic
Expand Down
30 changes: 18 additions & 12 deletions src/ros_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2001,18 +2001,7 @@ void RosFilter<T>::periodicUpdate()

rclcpp::Time cur_time = this->now();

if (toggled_on_) {
// Now we'll integrate any measurements we've received
integrateMeasurements(cur_time);
} else {
// Clear out measurements since we're not currently processing new entries
clearMeasurementQueue();

// Reset last measurement time so we don't get a large time delta on toggle
if (filter_.getInitializedStatus()) {
filter_.setLastMeasurementTime(this->now());
}
}
updateFilterWithMeasurements(cur_time);

// Get latest state and publish it
auto filtered_position = std::make_unique<nav_msgs::msg::Odometry>();
Expand Down Expand Up @@ -2174,6 +2163,23 @@ void RosFilter<T>::periodicUpdate()
}
}

template<typename T>
void RosFilter<T>::updateFilterWithMeasurements(const rclcpp::Time & time)
{
if (toggled_on_) {
// Now we'll integrate any measurements we've received
integrateMeasurements(time);
} else {
// Clear out measurements since we're not currently processing new entries
clearMeasurementQueue();

// Reset last measurement time so we don't get a large time delta on toggle
if (filter_.getInitializedStatus()) {
filter_.setLastMeasurementTime(time);
}
}
}

template<typename T>
void RosFilter<T>::setPoseCallback(
const geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg)
Expand Down