Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
simple_smoother.hpp
1 // Copyright (c) 2022, Samsung Research America
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. Reserved.
14 
15 #ifndef NAV2_SMOOTHER__SIMPLE_SMOOTHER_HPP_
16 #define NAV2_SMOOTHER__SIMPLE_SMOOTHER_HPP_
17 
18 #include <cmath>
19 #include <vector>
20 #include <string>
21 #include <iostream>
22 #include <memory>
23 #include <queue>
24 #include <utility>
25 
26 #include "nav2_core/smoother.hpp"
27 #include "nav2_smoother/smoother_utils.hpp"
28 #include "nav2_costmap_2d/costmap_2d.hpp"
29 #include "nav2_costmap_2d/cost_values.hpp"
30 #include "nav2_util/geometry_utils.hpp"
31 #include "nav2_ros_common/node_utils.hpp"
32 #include "nav_msgs/msg/path.hpp"
33 #include "angles/angles.h"
34 #include "tf2/utils.hpp"
35 #include "nav2_ros_common/lifecycle_node.hpp"
36 
37 namespace nav2_smoother
38 {
39 
45 {
46 public:
50  SimpleSmoother() = default;
51 
55  ~SimpleSmoother() override = default;
56 
57  void configure(
58  const nav2::LifecycleNode::WeakPtr &,
59  std::string name, std::shared_ptr<tf2_ros::Buffer>,
60  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber>,
61  std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>) override;
62 
66  void cleanup() override {costmap_sub_.reset();}
67 
71  void activate() override {}
72 
76  void deactivate() override {}
77 
85  bool smooth(
86  nav_msgs::msg::Path & path,
87  const rclcpp::Duration & max_time) override;
88 
89 protected:
97  void smoothImpl(
98  nav_msgs::msg::Path & path,
99  bool & reversing_segment,
100  const nav2_costmap_2d::Costmap2D * costmap,
101  const double & max_time);
102 
109  inline double getFieldByDim(
110  const geometry_msgs::msg::PoseStamped & msg,
111  const unsigned int & dim);
112 
119  inline void setFieldByDim(
120  geometry_msgs::msg::PoseStamped & msg, const unsigned int dim,
121  const double & value);
122 
123  double tolerance_, data_w_, smooth_w_;
124  int max_its_, refinement_ctr_, refinement_num_;
125  bool do_refinement_, enforce_path_inversion_;
126  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
127  rclcpp::Logger logger_{rclcpp::get_logger("SimpleSmoother")};
128 };
129 
130 } // namespace nav2_smoother
131 
132 #endif // NAV2_SMOOTHER__SIMPLE_SMOOTHER_HPP_
smoother interface that acts as a virtual base class for all smoother plugins
Definition: smoother.hpp:38
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
A path smoother implementation.
~SimpleSmoother() override=default
A destructor for nav2_smoother::SimpleSmoother.
void setFieldByDim(geometry_msgs::msg::PoseStamped &msg, const unsigned int dim, const double &value)
Set the field value for a given dimension.
void deactivate() override
Method to deactivate smoother and any threads involved in execution.
void activate() override
Method to activate smoother and any threads involved in execution.
SimpleSmoother()=default
A constructor for nav2_smoother::SimpleSmoother.
bool smooth(nav_msgs::msg::Path &path, const rclcpp::Duration &max_time) override
Method to smooth given path.
void smoothImpl(nav_msgs::msg::Path &path, bool &reversing_segment, const nav2_costmap_2d::Costmap2D *costmap, const double &max_time)
Smoother method - does the smoothing on a segment.
double getFieldByDim(const geometry_msgs::msg::PoseStamped &msg, const unsigned int &dim)
Get the field value for a given dimension.
void cleanup() override
Method to cleanup resources.