Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
constrained_smoother.hpp
1 // Copyright (c) 2021 RoboTech Vision
2 // Copyright (c) 2020 Shrijit Singh
3 // Copyright (c) 2020 Samsung Research America
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License.
16 
17 #ifndef NAV2_CONSTRAINED_SMOOTHER__CONSTRAINED_SMOOTHER_HPP_
18 #define NAV2_CONSTRAINED_SMOOTHER__CONSTRAINED_SMOOTHER_HPP_
19 
20 #include <string>
21 #include <vector>
22 #include <memory>
23 #include <algorithm>
24 
25 #include "nav2_core/smoother.hpp"
26 #include "nav2_constrained_smoother/smoother.hpp"
27 #include "rclcpp/rclcpp.hpp"
28 #include "nav2_util/odometry_utils.hpp"
29 #include "nav2_util/geometry_utils.hpp"
30 #include "geometry_msgs/msg/pose2_d.hpp"
31 
32 namespace nav2_constrained_smoother
33 {
34 
40 {
41 public:
45  ConstrainedSmoother() = default;
46 
50  ~ConstrainedSmoother() override = default;
51 
59  void configure(
60  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
61  std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
62  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub,
63  std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub) override;
64 
68  void cleanup() override;
69 
73  void activate() override;
74 
78  void deactivate() override;
79 
87  bool smooth(
88  nav_msgs::msg::Path & path,
89  const rclcpp::Duration & max_time) override;
90 
91 protected:
92  std::shared_ptr<tf2_ros::Buffer> tf_;
93  std::string plugin_name_;
94  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
95  rclcpp::Logger logger_ {rclcpp::get_logger("ConstrainedSmoother")};
96 
97  std::unique_ptr<nav2_constrained_smoother::Smoother> smoother_;
98  SmootherParams smoother_params_;
99  OptimizerParams optimizer_params_;
100 };
101 
102 } // namespace nav2_constrained_smoother
103 
104 #endif // NAV2_CONSTRAINED_SMOOTHER__CONSTRAINED_SMOOTHER_HPP_
Regulated pure pursuit controller plugin.
~ConstrainedSmoother() override=default
Destrructor for nav2_constrained_smoother::ConstrainedSmoother.
void activate() override
Activate controller state machine.
bool smooth(nav_msgs::msg::Path &path, const rclcpp::Duration &max_time) override
Method to smooth given path.
void cleanup() override
Cleanup controller state machine.
void deactivate() override
Deactivate controller state machine.
ConstrainedSmoother()=default
Constructor for nav2_constrained_smoother::ConstrainedSmoother.
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_sub, std::shared_ptr< nav2_costmap_2d::FootprintSubscriber > footprint_sub) override
Configure smoother parameters and member variables.
smoother interface that acts as a virtual base class for all smoother plugins
Definition: smoother.hpp:39