39 #include "nav2_controller/plugins/simple_goal_checker.hpp"
40 #include "pluginlib/class_list_macros.hpp"
41 #include "angles/angles.h"
42 #include "nav2_ros_common/node_utils.hpp"
43 #include "nav2_util/geometry_utils.hpp"
44 #pragma GCC diagnostic push
45 #pragma GCC diagnostic ignored "-Wpedantic"
46 #include "tf2/utils.hpp"
47 #pragma GCC diagnostic pop
49 using rcl_interfaces::msg::ParameterType;
50 using std::placeholders::_1;
52 namespace nav2_controller
55 SimpleGoalChecker::SimpleGoalChecker()
56 : xy_goal_tolerance_(0.25),
57 yaw_goal_tolerance_(0.25),
60 xy_goal_tolerance_sq_(0.0625)
64 void SimpleGoalChecker::initialize(
65 const nav2::LifecycleNode::WeakPtr & parent,
66 const std::string & plugin_name,
67 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS>)
69 plugin_name_ = plugin_name;
70 auto node = parent.lock();
72 xy_goal_tolerance_ = node->declare_or_get_parameter(plugin_name +
".xy_goal_tolerance", 0.25);
73 yaw_goal_tolerance_ = node->declare_or_get_parameter(plugin_name +
".yaw_goal_tolerance", 0.25);
74 stateful_ = node->declare_or_get_parameter(plugin_name +
".stateful",
true);
76 xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_;
79 dyn_params_handler_ = node->add_on_set_parameters_callback(
80 std::bind(&SimpleGoalChecker::dynamicParametersCallback,
this, _1));
83 void SimpleGoalChecker::reset()
88 bool SimpleGoalChecker::isGoalReached(
89 const geometry_msgs::msg::Pose & query_pose,
const geometry_msgs::msg::Pose & goal_pose,
90 const geometry_msgs::msg::Twist &)
93 double dx = query_pose.position.x - goal_pose.position.x,
94 dy = query_pose.position.y - goal_pose.position.y;
95 if (dx * dx + dy * dy > xy_goal_tolerance_sq_) {
104 double dyaw = angles::shortest_angular_distance(
105 tf2::getYaw(query_pose.orientation),
106 tf2::getYaw(goal_pose.orientation));
107 return fabs(dyaw) <= yaw_goal_tolerance_;
110 bool SimpleGoalChecker::getTolerances(
111 geometry_msgs::msg::Pose & pose_tolerance,
112 geometry_msgs::msg::Twist & vel_tolerance)
114 double invalid_field = std::numeric_limits<double>::lowest();
116 pose_tolerance.position.x = xy_goal_tolerance_;
117 pose_tolerance.position.y = xy_goal_tolerance_;
118 pose_tolerance.position.z = invalid_field;
119 pose_tolerance.orientation =
120 nav2_util::geometry_utils::orientationAroundZAxis(yaw_goal_tolerance_);
122 vel_tolerance.linear.x = invalid_field;
123 vel_tolerance.linear.y = invalid_field;
124 vel_tolerance.linear.z = invalid_field;
126 vel_tolerance.angular.x = invalid_field;
127 vel_tolerance.angular.y = invalid_field;
128 vel_tolerance.angular.z = invalid_field;
133 rcl_interfaces::msg::SetParametersResult
134 SimpleGoalChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
136 rcl_interfaces::msg::SetParametersResult result;
137 for (
auto & parameter : parameters) {
138 const auto & param_type = parameter.get_type();
139 const auto & param_name = parameter.get_name();
140 if (param_name.find(plugin_name_ +
".") != 0) {
143 if (param_type == ParameterType::PARAMETER_DOUBLE) {
144 if (param_name == plugin_name_ +
".xy_goal_tolerance") {
145 xy_goal_tolerance_ = parameter.as_double();
146 xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_;
147 }
else if (param_name == plugin_name_ +
".yaw_goal_tolerance") {
148 yaw_goal_tolerance_ = parameter.as_double();
150 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
151 if (param_name == plugin_name_ +
".stateful") {
152 stateful_ = parameter.as_bool();
156 result.successful =
true;
Goal Checker plugin that only checks the position difference.
Function-object for checking whether a goal has been reached.