Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
pose_progress_checker.cpp
1 // Copyright (c) 2023 Dexory
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/pose_progress_checker.hpp"
16 #include <cmath>
17 #include <string>
18 #include <memory>
19 #include <vector>
20 #include "angles/angles.h"
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 {
32 
34  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
35  const std::string & plugin_name)
36 {
37  plugin_name_ = plugin_name;
38  SimpleProgressChecker::initialize(parent, plugin_name);
39  auto node = parent.lock();
40 
41  nav2_util::declare_parameter_if_not_declared(
42  node, plugin_name + ".required_movement_angle", rclcpp::ParameterValue(0.5));
43  node->get_parameter_or(plugin_name + ".required_movement_angle", required_movement_angle_, 0.5);
44 
45  // Add callback for dynamic parameters
46  dyn_params_handler_ = node->add_on_set_parameters_callback(
48 }
49 
50 bool PoseProgressChecker::check(geometry_msgs::msg::PoseStamped & current_pose)
51 {
52  // relies on short circuit evaluation to not call is_robot_moved_enough if
53  // baseline_pose is not set.
54  geometry_msgs::msg::Pose2D current_pose2d;
55  current_pose2d = nav_2d_utils::poseToPose2D(current_pose.pose);
56 
57  if (!baseline_pose_set_ || PoseProgressChecker::isRobotMovedEnough(current_pose2d)) {
58  resetBaselinePose(current_pose2d);
59  return true;
60  }
61  return clock_->now() - baseline_time_ <= time_allowance_;
62 }
63 
64 bool PoseProgressChecker::isRobotMovedEnough(const geometry_msgs::msg::Pose2D & pose)
65 {
66  return pose_distance(pose, baseline_pose_) > radius_ ||
67  poseAngleDistance(pose, baseline_pose_) > required_movement_angle_;
68 }
69 
70 double PoseProgressChecker::poseAngleDistance(
71  const geometry_msgs::msg::Pose2D & pose1,
72  const geometry_msgs::msg::Pose2D & pose2)
73 {
74  return abs(angles::shortest_angular_distance(pose1.theta, pose2.theta));
75 }
76 
77 rcl_interfaces::msg::SetParametersResult
78 PoseProgressChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
79 {
80  rcl_interfaces::msg::SetParametersResult result;
81  for (auto parameter : parameters) {
82  const auto & param_type = parameter.get_type();
83  const auto & param_name = parameter.get_name();
84  if (param_name.find(plugin_name_ + ".") != 0) {
85  continue;
86  }
87 
88  if (param_type == ParameterType::PARAMETER_DOUBLE) {
89  if (param_name == plugin_name_ + ".required_movement_angle") {
90  required_movement_angle_ = parameter.as_double();
91  }
92  }
93  }
94  result.successful = true;
95  return result;
96 }
97 
98 } // namespace nav2_controller
99 
This plugin is used to check the position and the angle of the robot to make sure that it is actually...
bool isRobotMovedEnough(const geometry_msgs::msg::Pose2D &pose)
Calculates robots movement from baseline pose.
void initialize(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &plugin_name) override
Initialize parameters for ProgressChecker.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
bool check(geometry_msgs::msg::PoseStamped &current_pose) override
Checks if the robot has moved compare to previous pose.
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.
This class defines the plugin interface used to check the position of the robot to make sure that it ...