15 #include "nav2_controller/plugins/pose_progress_checker.hpp"
20 #include "angles/angles.h"
21 #include "geometry_msgs/msg/pose_stamped.hpp"
22 #include "geometry_msgs/msg/pose.hpp"
23 #include "nav2_ros_common/node_utils.hpp"
24 #include "pluginlib/class_list_macros.hpp"
25 #include "tf2/utils.hpp"
26 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
28 using rcl_interfaces::msg::ParameterType;
29 using std::placeholders::_1;
31 namespace nav2_controller
35 const nav2::LifecycleNode::WeakPtr & parent,
36 const std::string & plugin_name)
38 plugin_name_ = plugin_name;
40 auto node = parent.lock();
42 required_movement_angle_ = node->declare_or_get_parameter(
43 plugin_name +
".required_movement_angle", 0.5);
46 dyn_params_handler_ = node->add_on_set_parameters_callback(
58 return clock_->now() - baseline_time_ <= time_allowance_;
63 return pose_distance(pose, baseline_pose_) > radius_ ||
64 poseAngleDistance(pose, baseline_pose_) > required_movement_angle_;
67 double PoseProgressChecker::poseAngleDistance(
68 const geometry_msgs::msg::Pose & pose1,
69 const geometry_msgs::msg::Pose & pose2)
71 double theta1 = tf2::getYaw(pose1.orientation);
72 double theta2 = tf2::getYaw(pose2.orientation);
73 return std::abs(angles::shortest_angular_distance(theta1, theta2));
76 rcl_interfaces::msg::SetParametersResult
79 rcl_interfaces::msg::SetParametersResult result;
80 for (
auto parameter : parameters) {
81 const auto & param_type = parameter.get_type();
82 const auto & param_name = parameter.get_name();
83 if (param_name.find(plugin_name_ +
".") != 0) {
87 if (param_type == ParameterType::PARAMETER_DOUBLE) {
88 if (param_name == plugin_name_ +
".required_movement_angle") {
89 required_movement_angle_ = parameter.as_double();
93 result.successful =
true;
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.
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.
This class defines the plugin interface used to check the position of the robot to make sure that it ...