35 #ifndef NAV2_CONTROLLER__PLUGINS__STOPPED_GOAL_CHECKER_HPP_
36 #define NAV2_CONTROLLER__PLUGINS__STOPPED_GOAL_CHECKER_HPP_
42 #include "rclcpp/rclcpp.hpp"
43 #include "nav2_ros_common/lifecycle_node.hpp"
44 #include "nav2_controller/plugins/simple_goal_checker.hpp"
46 namespace nav2_controller
59 const nav2::LifecycleNode::WeakPtr & parent,
60 const std::string & plugin_name,
61 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
override;
63 const geometry_msgs::msg::Pose & query_pose,
const geometry_msgs::msg::Pose & goal_pose,
64 const geometry_msgs::msg::Twist & velocity)
override;
66 geometry_msgs::msg::Pose & pose_tolerance,
67 geometry_msgs::msg::Twist & vel_tolerance)
override;
70 double rot_stopped_velocity_, trans_stopped_velocity_;
72 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
73 std::string plugin_name_;
79 rcl_interfaces::msg::SetParametersResult
Goal Checker plugin that only checks the position difference.
Goal Checker plugin that checks the position difference and velocity.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter 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...
void initialize(const nav2::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.