Nav2 Navigation Stack - rolling  main
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 "geometry_msgs/msg/pose_stamped.hpp"
21 #include "geometry_msgs/msg/pose.hpp"
22 #include "nav2_ros_common/node_utils.hpp"
23 #include "pluginlib/class_list_macros.hpp"
24 
25 using rcl_interfaces::msg::ParameterType;
26 using std::placeholders::_1;
27 
28 namespace nav2_controller
29 {
31  const nav2::LifecycleNode::WeakPtr & parent,
32  const std::string & plugin_name)
33 {
34  plugin_name_ = plugin_name;
35  auto node = parent.lock();
36 
37  clock_ = node->get_clock();
38 
39  radius_ = node->declare_or_get_parameter(plugin_name + ".required_movement_radius", 0.5);
40  double time_allowance_param = node->declare_or_get_parameter(
41  plugin_name + ".movement_time_allowance", 10.0);
42  time_allowance_ = rclcpp::Duration::from_seconds(time_allowance_param);
43 
44  // Add callback for dynamic parameters
45  dyn_params_handler_ = node->add_on_set_parameters_callback(
47 }
48 
49 bool SimpleProgressChecker::check(geometry_msgs::msg::PoseStamped & current_pose)
50 {
51  // relies on short circuit evaluation to not call is_robot_moved_enough if
52  // baseline_pose is not set.
53  if ((!baseline_pose_set_) || (isRobotMovedEnough(current_pose.pose))) {
54  resetBaselinePose(current_pose.pose);
55  return true;
56  }
57  return !((clock_->now() - baseline_time_) > time_allowance_);
58 }
59 
61 {
62  baseline_pose_set_ = false;
63 }
64 
65 void SimpleProgressChecker::resetBaselinePose(const geometry_msgs::msg::Pose & pose)
66 {
67  baseline_pose_ = pose;
68  baseline_time_ = clock_->now();
69  baseline_pose_set_ = true;
70 }
71 
72 bool SimpleProgressChecker::isRobotMovedEnough(const geometry_msgs::msg::Pose & pose)
73 {
74  return pose_distance(pose, baseline_pose_) > radius_;
75 }
76 
77 double SimpleProgressChecker::pose_distance(
78  const geometry_msgs::msg::Pose & pose1,
79  const geometry_msgs::msg::Pose & pose2)
80 {
81  double dx = pose1.position.x - pose2.position.x;
82  double dy = pose1.position.y - pose2.position.y;
83 
84  return std::hypot(dx, dy);
85 }
86 
87 rcl_interfaces::msg::SetParametersResult
88 SimpleProgressChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
89 {
90  rcl_interfaces::msg::SetParametersResult result;
91  for (auto parameter : parameters) {
92  const auto & param_type = parameter.get_type();
93  const auto & param_name = parameter.get_name();
94  if (param_name.find(plugin_name_ + ".") != 0) {
95  continue;
96  }
97 
98  if (param_type == ParameterType::PARAMETER_DOUBLE) {
99  if (param_name == plugin_name_ + ".required_movement_radius") {
100  radius_ = parameter.as_double();
101  } else if (param_name == plugin_name_ + ".movement_time_allowance") {
102  time_allowance_ = rclcpp::Duration::from_seconds(parameter.as_double());
103  }
104  }
105  }
106  result.successful = true;
107  return result;
108 }
109 
110 } // namespace nav2_controller
111 
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 parameter change is detected.
void resetBaselinePose(const geometry_msgs::msg::Pose &pose)
Resets baseline pose with the current pose of the robot.
void initialize(const nav2::LifecycleNode::WeakPtr &parent, const std::string &plugin_name) override
Initialize parameters for ProgressChecker.
bool isRobotMovedEnough(const geometry_msgs::msg::Pose &pose)
Calculates robots movement from baseline pose.
void reset() override
Reset class state upon calling.
This class defines the plugin interface used to check the position of the robot to make sure that it ...