15 #ifndef ERROR_CODES__SMOOTHER__SMOOTHER_ERROR_PLUGIN_HPP_
16 #define ERROR_CODES__SMOOTHER__SMOOTHER_ERROR_PLUGIN_HPP_
21 #include "nav2_core/smoother.hpp"
22 #include "nav2_core/smoother_exceptions.hpp"
24 namespace nav2_system_tests
31 const nav2::LifecycleNode::WeakPtr &,
32 std::string, std::shared_ptr<tf2_ros::Buffer>,
33 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber>,
34 std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>)
override {}
43 nav_msgs::msg::Path &,
44 const rclcpp::Duration &)
override
53 nav_msgs::msg::Path &,
54 const rclcpp::Duration &)
63 nav_msgs::msg::Path &,
64 const rclcpp::Duration &)
73 nav_msgs::msg::Path &,
74 const rclcpp::Duration &)
83 nav_msgs::msg::Path &,
84 const rclcpp::Duration &)
smoother interface that acts as a virtual base class for all smoother plugins
void cleanup() override
Method to cleanup resources.
void deactivate() override
Method to deactivate smoother and any threads involved in execution.
bool smooth(nav_msgs::msg::Path &, const rclcpp::Duration &) override
Method to smooth given path.
void activate() override
Method to activate smoother and any threads involved in execution.