15 #ifndef NAV2_CONTROLLER__PLUGINS__POSE_PROGRESS_CHECKER_HPP_
16 #define NAV2_CONTROLLER__PLUGINS__POSE_PROGRESS_CHECKER_HPP_
20 #include "rclcpp/rclcpp.hpp"
21 #include "nav2_controller/plugins/simple_progress_checker.hpp"
22 #include "nav2_ros_common/lifecycle_node.hpp"
24 namespace nav2_controller
36 const nav2::LifecycleNode::WeakPtr & parent,
37 const std::string & plugin_name)
override;
38 bool check(geometry_msgs::msg::PoseStamped & current_pose)
override;
48 static double poseAngleDistance(
49 const geometry_msgs::msg::Pose &,
50 const geometry_msgs::msg::Pose &);
52 double required_movement_angle_;
55 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
56 std::string plugin_name_;
62 rcl_interfaces::msg::SetParametersResult
This plugin is used to check the position and the angle of the robot to make sure that it is actually...
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
bool isRobotMovedEnough(const geometry_msgs::msg::Pose &pose)
Calculates robots movement from baseline pose.
void initialize(const nav2::LifecycleNode::WeakPtr &parent, const std::string &plugin_name) override
Initialize parameters for ProgressChecker.
bool check(geometry_msgs::msg::PoseStamped ¤t_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...