Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
odometry_utils.hpp
1 // Copyright (c) 2018 Intel Corporation
2 // Copyright (c) 2020 Sarthak Mittal
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #ifndef NAV2_UTIL__ODOMETRY_UTILS_HPP_
17 #define NAV2_UTIL__ODOMETRY_UTILS_HPP_
18 
19 #include <cmath>
20 #include <chrono>
21 #include <memory>
22 #include <mutex>
23 #include <string>
24 #include <deque>
25 
26 #include "geometry_msgs/msg/twist.hpp"
27 #include "geometry_msgs/msg/twist_stamped.hpp"
28 #include "nav_msgs/msg/odometry.hpp"
29 #include "nav2_util/lifecycle_node.hpp"
30 #include "rclcpp/rclcpp.hpp"
31 #include "nav2_util/node_utils.hpp"
32 
33 namespace nav2_util
34 {
35 
42 {
43 public:
50  explicit OdomSmoother(
51  const rclcpp::Node::WeakPtr & parent,
52  double filter_duration = 0.3,
53  const std::string & odom_topic = "odom");
54 
62  explicit OdomSmoother(
63  const nav2_util::LifecycleNode::WeakPtr & parent,
64  double filter_duration = 0.3,
65  const std::string & odom_topic = "odom");
66 
71  inline geometry_msgs::msg::Twist getTwist() {return vel_smooth_.twist;}
72 
77  inline geometry_msgs::msg::TwistStamped getTwistStamped() {return vel_smooth_;}
78 
79 protected:
84  void odomCallback(nav_msgs::msg::Odometry::SharedPtr msg);
85 
89  void updateState();
90 
91  rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr odom_sub_;
92  nav_msgs::msg::Odometry odom_cumulate_;
93  geometry_msgs::msg::TwistStamped vel_smooth_;
94  std::mutex odom_mutex_;
95 
96  rclcpp::Duration odom_history_duration_;
97  std::deque<nav_msgs::msg::Odometry> odom_history_;
98 };
99 
100 } // namespace nav2_util
101 
102 #endif // NAV2_UTIL__ODOMETRY_UTILS_HPP_
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.
geometry_msgs::msg::Twist getTwist()
Get twist msg from smoother.
geometry_msgs::msg::TwistStamped getTwistStamped()
Get twist stamped msg from smoother.