Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
simple_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_CONTROLLER__PLUGINS__SIMPLE_GOAL_CHECKER_HPP_
36 #define NAV2_CONTROLLER__PLUGINS__SIMPLE_GOAL_CHECKER_HPP_
37 
38 #include <memory>
39 #include <string>
40 #include <vector>
41 
42 #include "rclcpp/rclcpp.hpp"
43 #include "rclcpp_lifecycle/lifecycle_node.hpp"
44 #include "nav2_core/goal_checker.hpp"
45 #include "rcl_interfaces/msg/set_parameters_result.hpp"
46 
47 namespace nav2_controller
48 {
49 
58 {
59 public:
61  // Standard GoalChecker Interface
62  void initialize(
63  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
64  const std::string & plugin_name,
65  const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
66  void reset() override;
67  bool isGoalReached(
68  const geometry_msgs::msg::Pose & query_pose, const geometry_msgs::msg::Pose & goal_pose,
69  const geometry_msgs::msg::Twist & velocity) override;
70  bool getTolerances(
71  geometry_msgs::msg::Pose & pose_tolerance,
72  geometry_msgs::msg::Twist & vel_tolerance) override;
73 
74 protected:
75  double xy_goal_tolerance_, yaw_goal_tolerance_;
76  bool stateful_, check_xy_;
77  // Cached squared xy_goal_tolerance_
78  double xy_goal_tolerance_sq_;
79  // Dynamic parameters handler
80  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
81  std::string plugin_name_;
82 
87  rcl_interfaces::msg::SetParametersResult
88  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
89 };
90 
91 } // namespace nav2_controller
92 
93 #endif // NAV2_CONTROLLER__PLUGINS__SIMPLE_GOAL_CHECKER_HPP_
Goal Checker plugin that only checks the position difference.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a paramter change is detected.
bool getTolerances(geometry_msgs::msg::Pose &pose_tolerance, geometry_msgs::msg::Twist &vel_tolerance) override
Get the maximum possible tolerances used for goal checking in the major types. Any field without a va...
bool isGoalReached(const geometry_msgs::msg::Pose &query_pose, const geometry_msgs::msg::Pose &goal_pose, const geometry_msgs::msg::Twist &velocity) override
Check whether the goal should be considered reached.
void initialize(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &plugin_name, const std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
Initialize any parameters from the NodeHandle.
Function-object for checking whether a goal has been reached.