Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
pose_filter.cpp
1 // Copyright (c) 2024 Open Navigation LLC
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "opennav_docking/pose_filter.hpp"
16 #include "rclcpp/rclcpp.hpp"
17 
18 namespace opennav_docking
19 {
20 
21 PoseFilter::PoseFilter(double coef, double timeout)
22 {
23  coef_ = coef;
24  timeout_ = timeout;
25  pose_.header.stamp = rclcpp::Time(0);
26 }
27 
28 geometry_msgs::msg::PoseStamped
29 PoseFilter::update(const geometry_msgs::msg::PoseStamped & measurement)
30 {
31  if (coef_ <= 0.0) {
32  // No filtering
33  return measurement;
34  }
35 
36  if ((rclcpp::Time(measurement.header.stamp) - pose_.header.stamp).seconds() > timeout_) {
37  pose_ = measurement;
38  } else if (pose_.header.frame_id != measurement.header.frame_id) {
39  pose_ = measurement;
40  } else {
41  // Copy header
42  pose_.header = measurement.header;
43 
44  // Filter position
45  filter(pose_.pose.position.x, measurement.pose.position.x);
46  filter(pose_.pose.position.y, measurement.pose.position.y);
47  filter(pose_.pose.position.z, measurement.pose.position.z);
48 
49  // Filter orientation
50  tf2::Quaternion f_quat, m_quat;
51  tf2::fromMsg(measurement.pose.orientation, m_quat);
52  tf2::fromMsg(pose_.pose.orientation, f_quat);
53  f_quat = f_quat.slerp(m_quat, coef_);
54  pose_.pose.orientation = tf2::toMsg(f_quat);
55  }
56 
57  return pose_;
58 }
59 
60 void PoseFilter::filter(double & filt, double meas)
61 {
62  filt = (1 - coef_) * filt + coef_ * meas;
63 }
64 
65 } // namespace opennav_docking
PoseFilter(double coef, double timeout)
Create a pose filter instance.
Definition: pose_filter.cpp:21
geometry_msgs::msg::PoseStamped update(const geometry_msgs::msg::PoseStamped &measurement)
Update the filter.
Definition: pose_filter.cpp:29