40 #include "nav2_controller/plugins/stopped_goal_checker.hpp"
41 #include "pluginlib/class_list_macros.hpp"
42 #include "nav2_util/node_utils.hpp"
47 using rcl_interfaces::msg::ParameterType;
48 using std::placeholders::_1;
50 namespace nav2_controller
53 StoppedGoalChecker::StoppedGoalChecker()
54 : SimpleGoalChecker(), rot_stopped_velocity_(0.25), trans_stopped_velocity_(0.25)
58 void StoppedGoalChecker::initialize(
59 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
60 const std::string & plugin_name,
61 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
63 plugin_name_ = plugin_name;
64 SimpleGoalChecker::initialize(parent, plugin_name, costmap_ros);
66 auto node = parent.lock();
68 nav2_util::declare_parameter_if_not_declared(
70 plugin_name +
".rot_stopped_velocity", rclcpp::ParameterValue(0.25));
71 nav2_util::declare_parameter_if_not_declared(
73 plugin_name +
".trans_stopped_velocity", rclcpp::ParameterValue(0.25));
75 node->get_parameter(plugin_name +
".rot_stopped_velocity", rot_stopped_velocity_);
76 node->get_parameter(plugin_name +
".trans_stopped_velocity", trans_stopped_velocity_);
79 dyn_params_handler_ = node->add_on_set_parameters_callback(
80 std::bind(&StoppedGoalChecker::dynamicParametersCallback,
this, _1));
83 bool StoppedGoalChecker::isGoalReached(
84 const geometry_msgs::msg::Pose & query_pose,
const geometry_msgs::msg::Pose & goal_pose,
85 const geometry_msgs::msg::Twist & velocity)
87 bool ret = SimpleGoalChecker::isGoalReached(query_pose, goal_pose, velocity);
92 return fabs(velocity.angular.z) <= rot_stopped_velocity_ &&
93 hypot(velocity.linear.x, velocity.linear.y) <= trans_stopped_velocity_;
96 bool StoppedGoalChecker::getTolerances(
97 geometry_msgs::msg::Pose & pose_tolerance,
98 geometry_msgs::msg::Twist & vel_tolerance)
100 double invalid_field = std::numeric_limits<double>::lowest();
103 bool rtn = SimpleGoalChecker::getTolerances(pose_tolerance, vel_tolerance);
106 vel_tolerance.linear.x = trans_stopped_velocity_;
107 vel_tolerance.linear.y = trans_stopped_velocity_;
108 vel_tolerance.linear.z = invalid_field;
110 vel_tolerance.angular.x = invalid_field;
111 vel_tolerance.angular.y = invalid_field;
112 vel_tolerance.angular.z = rot_stopped_velocity_;
117 rcl_interfaces::msg::SetParametersResult
118 StoppedGoalChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
120 rcl_interfaces::msg::SetParametersResult result;
121 for (
auto parameter : parameters) {
122 const auto & type = parameter.get_type();
123 const auto & name = parameter.get_name();
125 if (type == ParameterType::PARAMETER_DOUBLE) {
126 if (name == plugin_name_ +
".rot_stopped_velocity") {
127 rot_stopped_velocity_ = parameter.as_double();
128 }
else if (name == plugin_name_ +
".trans_stopped_velocity") {
129 trans_stopped_velocity_ = parameter.as_double();
133 result.successful =
true;
Goal Checker plugin that checks the position difference and velocity.
Function-object for checking whether a goal has been reached.