Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
simple_progress_checker.cpp
1 // Copyright (c) 2019 Intel Corporation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "nav2_controller/plugins/simple_progress_checker.hpp"
16 #include <cmath>
17 #include <string>
18 #include <memory>
19 #include <vector>
20 #include "nav2_core/exceptions.hpp"
21 #include "nav_2d_utils/conversions.hpp"
22 #include "geometry_msgs/msg/pose_stamped.hpp"
23 #include "geometry_msgs/msg/pose2_d.hpp"
24 #include "nav2_util/node_utils.hpp"
25 #include "pluginlib/class_list_macros.hpp"
26 
27 using rcl_interfaces::msg::ParameterType;
28 using std::placeholders::_1;
29 
30 namespace nav2_controller
31 {
33  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
34  const std::string & plugin_name)
35 {
36  plugin_name_ = plugin_name;
37  auto node = parent.lock();
38 
39  clock_ = node->get_clock();
40 
41  nav2_util::declare_parameter_if_not_declared(
42  node, plugin_name + ".required_movement_radius", rclcpp::ParameterValue(0.5));
43  nav2_util::declare_parameter_if_not_declared(
44  node, plugin_name + ".movement_time_allowance", rclcpp::ParameterValue(10.0));
45  // Scale is set to 0 by default, so if it was not set otherwise, set to 0
46  node->get_parameter_or(plugin_name + ".required_movement_radius", radius_, 0.5);
47  double time_allowance_param = 0.0;
48  node->get_parameter_or(plugin_name + ".movement_time_allowance", time_allowance_param, 10.0);
49  time_allowance_ = rclcpp::Duration::from_seconds(time_allowance_param);
50 
51  // Add callback for dynamic parameters
52  dyn_params_handler_ = node->add_on_set_parameters_callback(
54 }
55 
56 bool SimpleProgressChecker::check(geometry_msgs::msg::PoseStamped & current_pose)
57 {
58  // relies on short circuit evaluation to not call is_robot_moved_enough if
59  // baseline_pose is not set.
60  geometry_msgs::msg::Pose2D current_pose2d;
61  current_pose2d = nav_2d_utils::poseToPose2D(current_pose.pose);
62 
63  if ((!baseline_pose_set_) || (isRobotMovedEnough(current_pose2d))) {
64  resetBaselinePose(current_pose2d);
65  return true;
66  }
67  return !((clock_->now() - baseline_time_) > time_allowance_);
68 }
69 
71 {
72  baseline_pose_set_ = false;
73 }
74 
75 void SimpleProgressChecker::resetBaselinePose(const geometry_msgs::msg::Pose2D & pose)
76 {
77  baseline_pose_ = pose;
78  baseline_time_ = clock_->now();
79  baseline_pose_set_ = true;
80 }
81 
82 bool SimpleProgressChecker::isRobotMovedEnough(const geometry_msgs::msg::Pose2D & pose)
83 {
84  return pose_distance(pose, baseline_pose_) > radius_;
85 }
86 
87 double SimpleProgressChecker::pose_distance(
88  const geometry_msgs::msg::Pose2D & pose1,
89  const geometry_msgs::msg::Pose2D & pose2)
90 {
91  double dx = pose1.x - pose2.x;
92  double dy = pose1.y - pose2.y;
93 
94  return std::hypot(dx, dy);
95 }
96 
97 rcl_interfaces::msg::SetParametersResult
98 SimpleProgressChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
99 {
100  rcl_interfaces::msg::SetParametersResult result;
101  for (auto parameter : parameters) {
102  const auto & type = parameter.get_type();
103  const auto & name = parameter.get_name();
104 
105  if (type == ParameterType::PARAMETER_DOUBLE) {
106  if (name == plugin_name_ + ".required_movement_radius") {
107  radius_ = parameter.as_double();
108  } else if (name == plugin_name_ + ".movement_time_allowance") {
109  time_allowance_ = rclcpp::Duration::from_seconds(parameter.as_double());
110  }
111  }
112  }
113  result.successful = true;
114  return result;
115 }
116 
117 } // namespace nav2_controller
118 
This plugin is used to check the position of the robot to make sure that it is actually progressing t...
bool check(geometry_msgs::msg::PoseStamped &current_pose) override
Checks if the robot has moved compare to previous pose.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a paramter change is detected.
void reset() override
Reset class state upon calling.
void resetBaselinePose(const geometry_msgs::msg::Pose2D &pose)
Resets baseline pose with the current pose of the robot.
void initialize(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &plugin_name) override
Initialize parameters for ProgressChecker.
bool isRobotMovedEnough(const geometry_msgs::msg::Pose2D &pose)
Calculates robots movement from baseline pose.
This class defines the plugin interface used to check the position of the robot to make sure that it ...