Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
pose_progress_checker.hpp
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 #ifndef NAV2_CONTROLLER__PLUGINS__POSE_PROGRESS_CHECKER_HPP_
16 #define NAV2_CONTROLLER__PLUGINS__POSE_PROGRESS_CHECKER_HPP_
17 
18 #include <string>
19 #include <vector>
20 #include "rclcpp/rclcpp.hpp"
21 #include "nav2_controller/plugins/simple_progress_checker.hpp"
22 #include "rclcpp_lifecycle/lifecycle_node.hpp"
23 
24 namespace nav2_controller
25 {
33 {
34 public:
35  void initialize(
36  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
37  const std::string & plugin_name) override;
38  bool check(geometry_msgs::msg::PoseStamped & current_pose) override;
39 
40 protected:
46  bool isRobotMovedEnough(const geometry_msgs::msg::Pose2D & pose);
47 
48  static double poseAngleDistance(
49  const geometry_msgs::msg::Pose2D &,
50  const geometry_msgs::msg::Pose2D &);
51 
52  double required_movement_angle_;
53 
54  // Dynamic parameters handler
55  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
56  std::string plugin_name_;
57 
62  rcl_interfaces::msg::SetParametersResult
63  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
64 };
65 } // namespace nav2_controller
66 
67 #endif // NAV2_CONTROLLER__PLUGINS__POSE_PROGRESS_CHECKER_HPP_
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.
This plugin is used to check the position of the robot to make sure that it is actually progressing t...