Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
odometry_utils.cpp
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 #include <string>
17 
18 #include "nav2_util/odometry_utils.hpp"
19 
20 using namespace std::chrono; // NOLINT
21 using namespace std::chrono_literals; // NOLINT
22 
23 namespace nav2_util
24 {
25 
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))
31 {
32  auto node = parent.lock();
33  odom_sub_ = node->create_subscription<nav_msgs::msg::Odometry>(
34  odom_topic,
35  rclcpp::SystemDefaultsQoS(),
36  std::bind(&OdomSmoother::odomCallback, this, std::placeholders::_1));
37 
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;
44 }
45 
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))
51 {
52  auto node = parent.lock();
53  odom_sub_ = node->create_subscription<nav_msgs::msg::Odometry>(
54  odom_topic,
55  rclcpp::SystemDefaultsQoS(),
56  std::bind(&OdomSmoother::odomCallback, this, std::placeholders::_1));
57 
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;
64 }
65 
66 void OdomSmoother::odomCallback(const nav_msgs::msg::Odometry::SharedPtr msg)
67 {
68  std::lock_guard<std::mutex> lock(odom_mutex_);
69 
70  // update cumulated odom only if history is not empty
71  if (!odom_history_.empty()) {
72  // to store current time
73  auto current_time = rclcpp::Time(msg->header.stamp);
74 
75  // to store time of the first odom in history
76  auto front_time = rclcpp::Time(odom_history_.front().header.stamp);
77 
78  // update cumulated odom when duration has exceeded and pop earliest msg
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();
88 
89  if (odom_history_.empty()) {
90  break;
91  }
92 
93  // update with the timestamp of earliest odom message in history
94  front_time = rclcpp::Time(odom_history_.front().header.stamp);
95  }
96  }
97 
98  odom_history_.push_back(*msg);
99  updateState();
100 }
101 
103 {
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;
111 
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();
119 }
120 
121 } // namespace nav2_util
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.