18 #include "nav2_controller/plugins/position_goal_checker.hpp"
19 #include "pluginlib/class_list_macros.hpp"
20 #include "nav2_util/node_utils.hpp"
22 using rcl_interfaces::msg::ParameterType;
23 using std::placeholders::_1;
25 namespace nav2_controller
28 PositionGoalChecker::PositionGoalChecker()
29 : xy_goal_tolerance_(0.25),
30 xy_goal_tolerance_sq_(0.0625),
32 position_reached_(false)
36 void PositionGoalChecker::initialize(
37 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
38 const std::string & plugin_name,
39 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS>)
41 plugin_name_ = plugin_name;
42 auto node = parent.lock();
44 nav2_util::declare_parameter_if_not_declared(
46 plugin_name +
".xy_goal_tolerance", rclcpp::ParameterValue(0.25));
47 nav2_util::declare_parameter_if_not_declared(
49 plugin_name +
".stateful", rclcpp::ParameterValue(
true));
51 node->get_parameter(plugin_name +
".xy_goal_tolerance", xy_goal_tolerance_);
52 node->get_parameter(plugin_name +
".stateful", stateful_);
54 xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_;
57 dyn_params_handler_ = node->add_on_set_parameters_callback(
58 std::bind(&PositionGoalChecker::dynamicParametersCallback,
this, _1));
61 void PositionGoalChecker::reset()
63 position_reached_ =
false;
66 bool PositionGoalChecker::isGoalReached(
67 const geometry_msgs::msg::Pose & query_pose,
const geometry_msgs::msg::Pose & goal_pose,
68 const geometry_msgs::msg::Twist &)
71 if (stateful_ && position_reached_) {
76 double dx = query_pose.position.x - goal_pose.position.x;
77 double dy = query_pose.position.y - goal_pose.position.y;
79 bool position_reached = (dx * dx + dy * dy <= xy_goal_tolerance_sq_);
82 if (stateful_ && position_reached) {
83 position_reached_ =
true;
86 return position_reached;
89 bool PositionGoalChecker::getTolerances(
90 geometry_msgs::msg::Pose & pose_tolerance,
91 geometry_msgs::msg::Twist & vel_tolerance)
93 double invalid_field = std::numeric_limits<double>::lowest();
95 pose_tolerance.position.x = xy_goal_tolerance_;
96 pose_tolerance.position.y = xy_goal_tolerance_;
97 pose_tolerance.position.z = invalid_field;
100 pose_tolerance.orientation.x = 0.0;
101 pose_tolerance.orientation.y = 0.0;
102 pose_tolerance.orientation.z = 0.0;
103 pose_tolerance.orientation.w = 1.0;
105 vel_tolerance.linear.x = invalid_field;
106 vel_tolerance.linear.y = invalid_field;
107 vel_tolerance.linear.z = invalid_field;
109 vel_tolerance.angular.x = invalid_field;
110 vel_tolerance.angular.y = invalid_field;
111 vel_tolerance.angular.z = invalid_field;
118 xy_goal_tolerance_ = tolerance;
119 xy_goal_tolerance_sq_ = tolerance * tolerance;
122 rcl_interfaces::msg::SetParametersResult
125 rcl_interfaces::msg::SetParametersResult result;
126 for (
auto & parameter : parameters) {
127 const auto & type = parameter.get_type();
128 const auto & name = parameter.get_name();
130 if (type == ParameterType::PARAMETER_DOUBLE) {
131 if (name == plugin_name_ +
".xy_goal_tolerance") {
132 xy_goal_tolerance_ = parameter.as_double();
133 xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_;
135 }
else if (type == ParameterType::PARAMETER_BOOL) {
136 if (name == plugin_name_ +
".stateful") {
137 stateful_ = parameter.as_bool();
141 result.successful =
true;
Goal Checker plugin that only checks XY position, ignoring orientation.
void setXYGoalTolerance(double tolerance)
Set the XY goal tolerance.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
Function-object for checking whether a goal has been reached.