18 #include "nav2_util/odometry_utils.hpp"
20 using namespace std::chrono;
21 using namespace std::chrono_literals;
26 OdomSmoother::OdomSmoother(
27 const rclcpp::Node::WeakPtr & parent,
28 double filter_duration,
29 const std::string & odom_topic)
30 : odom_history_duration_(rclcpp::Duration::from_seconds(filter_duration))
32 auto node = parent.lock();
33 odom_sub_ = node->create_subscription<nav_msgs::msg::Odometry>(
35 rclcpp::SystemDefaultsQoS(),
38 odom_cumulate_.twist.twist.linear.x = 0;
39 odom_cumulate_.twist.twist.linear.y = 0;
40 odom_cumulate_.twist.twist.linear.z = 0;
41 odom_cumulate_.twist.twist.angular.x = 0;
42 odom_cumulate_.twist.twist.angular.y = 0;
43 odom_cumulate_.twist.twist.angular.z = 0;
47 const nav2_util::LifecycleNode::WeakPtr & parent,
48 double filter_duration,
49 const std::string & odom_topic)
50 : odom_history_duration_(rclcpp::Duration::from_seconds(filter_duration))
52 auto node = parent.lock();
53 odom_sub_ = node->create_subscription<nav_msgs::msg::Odometry>(
55 rclcpp::SystemDefaultsQoS(),
58 odom_cumulate_.twist.twist.linear.x = 0;
59 odom_cumulate_.twist.twist.linear.y = 0;
60 odom_cumulate_.twist.twist.linear.z = 0;
61 odom_cumulate_.twist.twist.angular.x = 0;
62 odom_cumulate_.twist.twist.angular.y = 0;
63 odom_cumulate_.twist.twist.angular.z = 0;
68 std::lock_guard<std::mutex> lock(odom_mutex_);
71 if (!odom_history_.empty()) {
73 auto current_time = rclcpp::Time(msg->header.stamp);
76 auto front_time = rclcpp::Time(odom_history_.front().header.stamp);
79 while (current_time - front_time > odom_history_duration_) {
80 const auto & odom = odom_history_.front();
81 odom_cumulate_.twist.twist.linear.x -= odom.twist.twist.linear.x;
82 odom_cumulate_.twist.twist.linear.y -= odom.twist.twist.linear.y;
83 odom_cumulate_.twist.twist.linear.z -= odom.twist.twist.linear.z;
84 odom_cumulate_.twist.twist.angular.x -= odom.twist.twist.angular.x;
85 odom_cumulate_.twist.twist.angular.y -= odom.twist.twist.angular.y;
86 odom_cumulate_.twist.twist.angular.z -= odom.twist.twist.angular.z;
87 odom_history_.pop_front();
89 if (odom_history_.empty()) {
94 front_time = rclcpp::Time(odom_history_.front().header.stamp);
98 odom_history_.push_back(*msg);
104 const auto & odom = odom_history_.back();
105 odom_cumulate_.twist.twist.linear.x += odom.twist.twist.linear.x;
106 odom_cumulate_.twist.twist.linear.y += odom.twist.twist.linear.y;
107 odom_cumulate_.twist.twist.linear.z += odom.twist.twist.linear.z;
108 odom_cumulate_.twist.twist.angular.x += odom.twist.twist.angular.x;
109 odom_cumulate_.twist.twist.angular.y += odom.twist.twist.angular.y;
110 odom_cumulate_.twist.twist.angular.z += odom.twist.twist.angular.z;
112 vel_smooth_.header = odom.header;
113 vel_smooth_.twist.linear.x = odom_cumulate_.twist.twist.linear.x / odom_history_.size();
114 vel_smooth_.twist.linear.y = odom_cumulate_.twist.twist.linear.y / odom_history_.size();
115 vel_smooth_.twist.linear.z = odom_cumulate_.twist.twist.linear.z / odom_history_.size();
116 vel_smooth_.twist.angular.x = odom_cumulate_.twist.twist.angular.x / odom_history_.size();
117 vel_smooth_.twist.angular.y = odom_cumulate_.twist.twist.angular.y / odom_history_.size();
118 vel_smooth_.twist.angular.z = odom_cumulate_.twist.twist.angular.z / odom_history_.size();
OdomSmoother(const rclcpp::Node::WeakPtr &parent, double filter_duration=0.3, const std::string &odom_topic="odom")
Constructor that subscribes to an Odometry topic.
void odomCallback(nav_msgs::msg::Odometry::SharedPtr msg)
Callback of odometry subscriber to process.
void updateState()
Update internal state of the smoother after getting new data.