15 #ifndef ERROR_CODES__CONTROLLER__CONTROLLER_ERROR_PLUGINS_HPP_
16 #define ERROR_CODES__CONTROLLER__CONTROLLER_ERROR_PLUGINS_HPP_
21 #include "nav2_core/controller.hpp"
22 #include "nav2_core/controller_exceptions.hpp"
24 namespace nav2_system_tests
34 const nav2::LifecycleNode::WeakPtr &,
35 std::string, std::shared_ptr<tf2_ros::Buffer>,
36 std::shared_ptr<nav2_costmap_2d::Costmap2DROS>)
override {}
44 void setPlan(
const nav_msgs::msg::Path &) {}
47 const geometry_msgs::msg::PoseStamped &,
48 const geometry_msgs::msg::Twist &,
59 virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(
60 const geometry_msgs::msg::PoseStamped &,
61 const geometry_msgs::msg::Twist &,
70 virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(
71 const geometry_msgs::msg::PoseStamped &,
72 const geometry_msgs::msg::Twist &,
81 virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(
82 const geometry_msgs::msg::PoseStamped &,
83 const geometry_msgs::msg::Twist &,
92 virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(
93 const geometry_msgs::msg::PoseStamped &,
94 const geometry_msgs::msg::Twist &,
103 virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(
104 const geometry_msgs::msg::PoseStamped &,
105 const geometry_msgs::msg::Twist &,
controller interface that acts as a virtual base class for all controller plugins
Function-object for checking whether a goal has been reached.
void deactivate()
Method to deactivate planner and any threads involved in execution.
void setSpeedLimit(const double &, const bool &)
Limits the maximum linear speed of the robot.
void setPlan(const nav_msgs::msg::Path &)
local setPlan - Sets the global plan
void configure(const nav2::LifecycleNode::WeakPtr &, std::string, std::shared_ptr< tf2_ros::Buffer >, std::shared_ptr< nav2_costmap_2d::Costmap2DROS >) override
void activate()
Method to active planner and any threads involved in execution.
void cleanup()
Method to cleanup resources.
virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(const geometry_msgs::msg::PoseStamped &, const geometry_msgs::msg::Twist &, nav2_core::GoalChecker *)
Controller computeVelocityCommands - calculates the best command given the current pose and velocity.