Nav2 Navigation Stack - rolling  main
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 void OdomSmoother::odomCallback(const nav_msgs::msg::Odometry::SharedPtr msg)
27 {
28  std::lock_guard<std::mutex> lock(odom_mutex_);
29  received_odom_ = true;
30 
31  // update cumulated odom only if history is not empty
32  if (!odom_history_.empty()) {
33  // to store current time
34  auto current_time = rclcpp::Time(msg->header.stamp);
35 
36  // to store time of the first odom in history
37  auto front_time = rclcpp::Time(odom_history_.front().header.stamp);
38 
39  // update cumulated odom when duration has exceeded and pop earliest msg
40  while (current_time - front_time > odom_history_duration_) {
41  const auto & odom = odom_history_.front();
42  odom_cumulate_.twist.twist.linear.x -= odom.twist.twist.linear.x;
43  odom_cumulate_.twist.twist.linear.y -= odom.twist.twist.linear.y;
44  odom_cumulate_.twist.twist.linear.z -= odom.twist.twist.linear.z;
45  odom_cumulate_.twist.twist.angular.x -= odom.twist.twist.angular.x;
46  odom_cumulate_.twist.twist.angular.y -= odom.twist.twist.angular.y;
47  odom_cumulate_.twist.twist.angular.z -= odom.twist.twist.angular.z;
48  odom_history_.pop_front();
49 
50  if (odom_history_.empty()) {
51  break;
52  }
53 
54  // update with the timestamp of earliest odom message in history
55  front_time = rclcpp::Time(odom_history_.front().header.stamp);
56  }
57  }
58 
59  odom_history_.push_back(*msg);
60  updateState();
61 }
62 
63 void OdomSmoother::updateState()
64 {
65  const auto & odom = odom_history_.back();
66  odom_cumulate_.twist.twist.linear.x += odom.twist.twist.linear.x;
67  odom_cumulate_.twist.twist.linear.y += odom.twist.twist.linear.y;
68  odom_cumulate_.twist.twist.linear.z += odom.twist.twist.linear.z;
69  odom_cumulate_.twist.twist.angular.x += odom.twist.twist.angular.x;
70  odom_cumulate_.twist.twist.angular.y += odom.twist.twist.angular.y;
71  odom_cumulate_.twist.twist.angular.z += odom.twist.twist.angular.z;
72 
73  vel_smooth_.header = odom.header;
74  vel_smooth_.twist.linear.x = odom_cumulate_.twist.twist.linear.x / odom_history_.size();
75  vel_smooth_.twist.linear.y = odom_cumulate_.twist.twist.linear.y / odom_history_.size();
76  vel_smooth_.twist.linear.z = odom_cumulate_.twist.twist.linear.z / odom_history_.size();
77  vel_smooth_.twist.angular.x = odom_cumulate_.twist.twist.angular.x / odom_history_.size();
78  vel_smooth_.twist.angular.y = odom_cumulate_.twist.twist.angular.y / odom_history_.size();
79  vel_smooth_.twist.angular.z = odom_cumulate_.twist.twist.angular.z / odom_history_.size();
80 }
81 
82 } // namespace nav2_util