40 #include "nav2_controller/plugins/stopped_goal_checker.hpp"
41 #include "pluginlib/class_list_macros.hpp"
42 #include "nav2_ros_common/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 nav2::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 rot_stopped_velocity_ = node->declare_or_get_parameter(
69 plugin_name +
".rot_stopped_velocity", 0.25);
70 trans_stopped_velocity_ = node->declare_or_get_parameter(
71 plugin_name +
".trans_stopped_velocity", 0.25);
74 dyn_params_handler_ = node->add_on_set_parameters_callback(
75 std::bind(&StoppedGoalChecker::dynamicParametersCallback,
this, _1));
78 bool StoppedGoalChecker::isGoalReached(
79 const geometry_msgs::msg::Pose & query_pose,
const geometry_msgs::msg::Pose & goal_pose,
80 const geometry_msgs::msg::Twist & velocity)
82 bool ret = SimpleGoalChecker::isGoalReached(query_pose, goal_pose, velocity);
87 return fabs(velocity.angular.z) <= rot_stopped_velocity_ &&
88 hypot(velocity.linear.x, velocity.linear.y) <= trans_stopped_velocity_;
91 bool StoppedGoalChecker::getTolerances(
92 geometry_msgs::msg::Pose & pose_tolerance,
93 geometry_msgs::msg::Twist & vel_tolerance)
95 double invalid_field = std::numeric_limits<double>::lowest();
98 bool rtn = SimpleGoalChecker::getTolerances(pose_tolerance, vel_tolerance);
101 vel_tolerance.linear.x = trans_stopped_velocity_;
102 vel_tolerance.linear.y = trans_stopped_velocity_;
103 vel_tolerance.linear.z = invalid_field;
105 vel_tolerance.angular.x = invalid_field;
106 vel_tolerance.angular.y = invalid_field;
107 vel_tolerance.angular.z = rot_stopped_velocity_;
112 rcl_interfaces::msg::SetParametersResult
113 StoppedGoalChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
115 rcl_interfaces::msg::SetParametersResult result;
116 for (
auto parameter : parameters) {
117 const auto & param_type = parameter.get_type();
118 const auto & param_name = parameter.get_name();
119 if (param_name.find(plugin_name_ +
".") != 0) {
123 if (param_type == ParameterType::PARAMETER_DOUBLE) {
124 if (param_name == plugin_name_ +
".rot_stopped_velocity") {
125 rot_stopped_velocity_ = parameter.as_double();
126 }
else if (param_name == plugin_name_ +
".trans_stopped_velocity") {
127 trans_stopped_velocity_ = parameter.as_double();
131 result.successful =
true;
Goal Checker plugin that checks the position difference and velocity.
Function-object for checking whether a goal has been reached.