Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
goal_checker.hpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #ifndef NAV2_CORE__GOAL_CHECKER_HPP_
36 #define NAV2_CORE__GOAL_CHECKER_HPP_
37 
38 #include <memory>
39 #include <string>
40 
41 #include "rclcpp/rclcpp.hpp"
42 #include "rclcpp_lifecycle/lifecycle_node.hpp"
43 #include "geometry_msgs/msg/pose.hpp"
44 #include "geometry_msgs/msg/twist.hpp"
45 
46 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
47 
48 
49 namespace nav2_core
50 {
51 
62 {
63 public:
64  typedef std::shared_ptr<nav2_core::GoalChecker> Ptr;
65 
66  virtual ~GoalChecker() {}
67 
72  virtual void initialize(
73  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
74  const std::string & plugin_name,
75  const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) = 0;
76 
77  virtual void reset() = 0;
78 
86  virtual bool isGoalReached(
87  const geometry_msgs::msg::Pose & query_pose, const geometry_msgs::msg::Pose & goal_pose,
88  const geometry_msgs::msg::Twist & velocity) = 0;
89 
100  virtual bool getTolerances(
101  geometry_msgs::msg::Pose & pose_tolerance,
102  geometry_msgs::msg::Twist & vel_tolerance) = 0;
103 };
104 
105 } // namespace nav2_core
106 
107 #endif // NAV2_CORE__GOAL_CHECKER_HPP_
Function-object for checking whether a goal has been reached.
virtual bool isGoalReached(const geometry_msgs::msg::Pose &query_pose, const geometry_msgs::msg::Pose &goal_pose, const geometry_msgs::msg::Twist &velocity)=0
Check whether the goal should be considered reached.
virtual void initialize(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &plugin_name, const std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros)=0
Initialize any parameters from the NodeHandle.
virtual bool getTolerances(geometry_msgs::msg::Pose &pose_tolerance, geometry_msgs::msg::Twist &vel_tolerance)=0
Get the maximum possible tolerances used for goal checking in the major types. Any field without a va...