Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
behavior.hpp
1 // Copyright (c) 2019 Samsung Research America
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_CORE__BEHAVIOR_HPP_
16 #define NAV2_CORE__BEHAVIOR_HPP_
17 
18 #include <string>
19 #include <memory>
20 
21 #include "rclcpp/rclcpp.hpp"
22 #include "nav2_util/lifecycle_node.hpp"
23 #include "tf2_ros/buffer.h"
24 #include "nav2_costmap_2d/costmap_topic_collision_checker.hpp"
25 
26 namespace nav2_core
27 {
28 
29 enum class CostmapInfoType
30 {
31  NONE = 0,
32  LOCAL = 1,
33  GLOBAL = 2,
34  BOTH = 3
35 };
36 
41 class Behavior
42 {
43 public:
44  using Ptr = std::shared_ptr<Behavior>;
45 
49  virtual ~Behavior() {}
50 
57  virtual void configure(
58  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
59  const std::string & name, std::shared_ptr<tf2_ros::Buffer> tf,
60  std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> local_collision_checker,
61  std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> global_collision_checker) = 0;
62 
66  virtual void cleanup() = 0;
67 
71  virtual void activate() = 0;
72 
76  virtual void deactivate() = 0;
77 
82  virtual CostmapInfoType getResourceInfo() = 0;
83 };
84 
85 } // namespace nav2_core
86 
87 #endif // NAV2_CORE__BEHAVIOR_HPP_
Abstract interface for behaviors to adhere to with pluginlib.
Definition: behavior.hpp:42
virtual void cleanup()=0
Method to cleanup resources used on shutdown.
virtual ~Behavior()
Virtual destructor.
Definition: behavior.hpp:49
virtual void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > local_collision_checker, std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > global_collision_checker)=0
virtual void activate()=0
Method to active Behavior and any threads involved in execution.
virtual CostmapInfoType getResourceInfo()=0
Method to determine the required costmap info.
virtual void deactivate()=0
Method to deactivate Behavior and any threads involved in execution.