Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
controller.hpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * Copyright (c) 2019, Intel Corporation
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the copyright holder nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
36 #ifndef NAV2_CORE__CONTROLLER_HPP_
37 #define NAV2_CORE__CONTROLLER_HPP_
38 
39 #include <memory>
40 #include <string>
41 
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"
51 
52 
53 namespace nav2_core
54 {
55 
61 {
62 public:
63  using Ptr = std::shared_ptr<nav2_core::Controller>;
64 
65 
69  virtual ~Controller() {}
70 
75  virtual void configure(
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;
79 
83  virtual void cleanup() = 0;
84 
88  virtual void activate() = 0;
89 
93  virtual void deactivate() = 0;
94 
99  virtual void setPlan(const nav_msgs::msg::Path & path) = 0;
100 
114  virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(
115  const geometry_msgs::msg::PoseStamped & pose,
116  const geometry_msgs::msg::Twist & velocity,
117  nav2_core::GoalChecker * goal_checker) = 0;
118 
124  virtual bool cancel()
125  {
126  return true;
127  }
128 
136  virtual void setSpeedLimit(const double & speed_limit, const bool & percentage) = 0;
137 
141  virtual void reset() {}
142 };
143 
144 } // namespace nav2_core
145 
146 #endif // NAV2_CORE__CONTROLLER_HPP_
controller interface that acts as a virtual base class for all controller plugins
Definition: controller.hpp:61
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.
Definition: controller.hpp:69
virtual void setPlan(const nav_msgs::msg::Path &path)=0
local setPlan - Sets the global plan
virtual bool cancel()
Cancel the current control action.
Definition: controller.hpp:124
virtual void reset()
Reset the state of the controller if necessary after task is exited.
Definition: controller.hpp:141
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.