15 #ifndef NAV2_CONTROLLER__PLUGINS__POSITION_GOAL_CHECKER_HPP_
16 #define NAV2_CONTROLLER__PLUGINS__POSITION_GOAL_CHECKER_HPP_
21 #include "rclcpp/rclcpp.hpp"
22 #include "rclcpp_lifecycle/lifecycle_node.hpp"
23 #include "nav2_core/goal_checker.hpp"
24 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
26 namespace nav2_controller
40 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
41 const std::string & plugin_name,
42 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
override;
44 void reset()
override;
47 const geometry_msgs::msg::Pose & query_pose,
const geometry_msgs::msg::Pose & goal_pose,
48 const geometry_msgs::msg::Twist & velocity)
override;
51 geometry_msgs::msg::Pose & pose_tolerance,
52 geometry_msgs::msg::Twist & vel_tolerance)
override;
61 double xy_goal_tolerance_;
62 double xy_goal_tolerance_sq_;
64 bool position_reached_;
65 std::string plugin_name_;
66 rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
72 rcl_interfaces::msg::SetParametersResult
Goal Checker plugin that only checks XY position, ignoring orientation.
void setXYGoalTolerance(double tolerance)
Set the XY goal tolerance.
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...
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
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.
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.
Function-object for checking whether a goal has been reached.