Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
simple_progress_checker.hpp
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 #ifndef NAV2_CONTROLLER__PLUGINS__SIMPLE_PROGRESS_CHECKER_HPP_
16 #define NAV2_CONTROLLER__PLUGINS__SIMPLE_PROGRESS_CHECKER_HPP_
17 
18 #include <string>
19 #include <vector>
20 #include "rclcpp/rclcpp.hpp"
21 #include "nav2_ros_common/lifecycle_node.hpp"
22 #include "nav2_core/progress_checker.hpp"
23 #include "geometry_msgs/msg/pose_stamped.hpp"
24 #include "geometry_msgs/msg/pose.hpp"
25 
26 namespace nav2_controller
27 {
35 {
36 public:
37  void initialize(
38  const nav2::LifecycleNode::WeakPtr & parent,
39  const std::string & plugin_name) override;
40  bool check(geometry_msgs::msg::PoseStamped & current_pose) override;
41  void reset() override;
42 
43 protected:
49  bool isRobotMovedEnough(const geometry_msgs::msg::Pose & pose);
54  void resetBaselinePose(const geometry_msgs::msg::Pose & pose);
55 
56  static double pose_distance(
57  const geometry_msgs::msg::Pose &,
58  const geometry_msgs::msg::Pose &);
59 
60  rclcpp::Clock::SharedPtr clock_;
61 
62  double radius_;
63  rclcpp::Duration time_allowance_{0, 0};
64 
65  geometry_msgs::msg::Pose baseline_pose_;
66  rclcpp::Time baseline_time_;
67 
68  bool baseline_pose_set_{false};
69  // Dynamic parameters handler
70  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
71  std::string plugin_name_;
72 
77  rcl_interfaces::msg::SetParametersResult
78  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
79 };
80 } // namespace nav2_controller
81 
82 #endif // NAV2_CONTROLLER__PLUGINS__SIMPLE_PROGRESS_CHECKER_HPP_
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 ...