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 nav2::declare_parameter_if_not_declared(
74 plugin_name +
".xy_goal_tolerance", rclcpp::ParameterValue(0.25));
75 nav2::declare_parameter_if_not_declared(
77 plugin_name +
".yaw_goal_tolerance", rclcpp::ParameterValue(0.25));
78 nav2::declare_parameter_if_not_declared(
80 plugin_name +
".stateful", rclcpp::ParameterValue(
true));
82 node->get_parameter(plugin_name +
".xy_goal_tolerance", xy_goal_tolerance_);
83 node->get_parameter(plugin_name +
".yaw_goal_tolerance", yaw_goal_tolerance_);
84 node->get_parameter(plugin_name +
".stateful", stateful_);
86 xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_;
89 dyn_params_handler_ = node->add_on_set_parameters_callback(
90 std::bind(&SimpleGoalChecker::dynamicParametersCallback,
this, _1));
93 void SimpleGoalChecker::reset()
98 bool SimpleGoalChecker::isGoalReached(
99 const geometry_msgs::msg::Pose & query_pose,
const geometry_msgs::msg::Pose & goal_pose,
100 const geometry_msgs::msg::Twist &)
103 double dx = query_pose.position.x - goal_pose.position.x,
104 dy = query_pose.position.y - goal_pose.position.y;
105 if (dx * dx + dy * dy > xy_goal_tolerance_sq_) {
114 double dyaw = angles::shortest_angular_distance(
115 tf2::getYaw(query_pose.orientation),
116 tf2::getYaw(goal_pose.orientation));
117 return fabs(dyaw) <= yaw_goal_tolerance_;
120 bool SimpleGoalChecker::getTolerances(
121 geometry_msgs::msg::Pose & pose_tolerance,
122 geometry_msgs::msg::Twist & vel_tolerance)
124 double invalid_field = std::numeric_limits<double>::lowest();
126 pose_tolerance.position.x = xy_goal_tolerance_;
127 pose_tolerance.position.y = xy_goal_tolerance_;
128 pose_tolerance.position.z = invalid_field;
129 pose_tolerance.orientation =
130 nav2_util::geometry_utils::orientationAroundZAxis(yaw_goal_tolerance_);
132 vel_tolerance.linear.x = invalid_field;
133 vel_tolerance.linear.y = invalid_field;
134 vel_tolerance.linear.z = invalid_field;
136 vel_tolerance.angular.x = invalid_field;
137 vel_tolerance.angular.y = invalid_field;
138 vel_tolerance.angular.z = invalid_field;
143 rcl_interfaces::msg::SetParametersResult
144 SimpleGoalChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
146 rcl_interfaces::msg::SetParametersResult result;
147 for (
auto & parameter : parameters) {
148 const auto & param_type = parameter.get_type();
149 const auto & param_name = parameter.get_name();
150 if (param_name.find(plugin_name_ +
".") != 0) {
153 if (param_type == ParameterType::PARAMETER_DOUBLE) {
154 if (param_name == plugin_name_ +
".xy_goal_tolerance") {
155 xy_goal_tolerance_ = parameter.as_double();
156 xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_;
157 }
else if (param_name == plugin_name_ +
".yaw_goal_tolerance") {
158 yaw_goal_tolerance_ = parameter.as_double();
160 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
161 if (param_name == plugin_name_ +
".stateful") {
162 stateful_ = parameter.as_bool();
166 result.successful =
true;
Goal Checker plugin that only checks the position difference.
Function-object for checking whether a goal has been reached.