15 #include "nav2_controller/plugins/pose_progress_checker.hpp"
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"
27 using rcl_interfaces::msg::ParameterType;
28 using std::placeholders::_1;
30 namespace nav2_controller
34 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
35 const std::string & plugin_name)
37 plugin_name_ = plugin_name;
39 auto node = parent.lock();
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);
46 dyn_params_handler_ = node->add_on_set_parameters_callback(
54 geometry_msgs::msg::Pose2D current_pose2d;
55 current_pose2d = nav_2d_utils::poseToPose2D(current_pose.pose);
61 return clock_->now() - baseline_time_ <= time_allowance_;
66 return pose_distance(pose, baseline_pose_) > radius_ ||
67 poseAngleDistance(pose, baseline_pose_) > required_movement_angle_;
70 double PoseProgressChecker::poseAngleDistance(
71 const geometry_msgs::msg::Pose2D & pose1,
72 const geometry_msgs::msg::Pose2D & pose2)
74 return abs(angles::shortest_angular_distance(pose1.theta, pose2.theta));
77 rcl_interfaces::msg::SetParametersResult
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) {
88 if (param_type == ParameterType::PARAMETER_DOUBLE) {
89 if (param_name == plugin_name_ +
".required_movement_angle") {
90 required_movement_angle_ = parameter.as_double();
94 result.successful =
true;
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 ¤t_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 ...