36 #ifndef NAV2_CORE__CONTROLLER_HPP_
37 #define NAV2_CORE__CONTROLLER_HPP_
42 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
43 #include "tf2_ros/transform_listener.h"
44 #include "rclcpp/rclcpp.hpp"
45 #include "rclcpp_lifecycle/lifecycle_node.hpp"
46 #include "pluginlib/class_loader.hpp"
47 #include "geometry_msgs/msg/pose_stamped.hpp"
48 #include "geometry_msgs/msg/twist_stamped.hpp"
49 #include "nav_msgs/msg/path.hpp"
50 #include "nav2_core/goal_checker.hpp"
63 using Ptr = std::shared_ptr<nav2_core::Controller>;
76 const rclcpp_lifecycle::LifecycleNode::WeakPtr &,
77 std::string name, std::shared_ptr<tf2_ros::Buffer>,
78 std::shared_ptr<nav2_costmap_2d::Costmap2DROS>) = 0;
99 virtual void setPlan(
const nav_msgs::msg::Path & path) = 0;
115 const geometry_msgs::msg::PoseStamped & pose,
116 const geometry_msgs::msg::Twist & velocity,
126 virtual void setSpeedLimit(
const double & speed_limit,
const bool & percentage) = 0;
controller interface that acts as a virtual base class for all controller plugins
virtual void activate()=0
Method to active planner and any threads involved in execution.
virtual void deactivate()=0
Method to deactive planner and any threads involved in execution.
virtual void setSpeedLimit(const double &speed_limit, const bool &percentage)=0
Limits the maximum linear speed of the robot.
virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity, nav2_core::GoalChecker *goal_checker)=0
Controller computeVelocityCommands - calculates the best command given the current pose and velocity.
virtual void cleanup()=0
Method to cleanup resources.
virtual ~Controller()
Virtual destructor.
virtual void setPlan(const nav_msgs::msg::Path &path)=0
local setPlan - Sets the global plan
virtual void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &, std::string name, std::shared_ptr< tf2_ros::Buffer >, std::shared_ptr< nav2_costmap_2d::Costmap2DROS >)=0
Function-object for checking whether a goal has been reached.