|
Nav2 Navigation Stack - jazzy
jazzy
ROS 2 Navigation Stack
|
This plugin is used to check the position and the angle of the robot to make sure that it is actually progressing or rotating towards a goal. More...
#include <nav2_controller/include/nav2_controller/plugins/pose_progress_checker.hpp>


Public Member Functions | |
| void | initialize (const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &plugin_name) override |
| Initialize parameters for ProgressChecker. More... | |
| bool | check (geometry_msgs::msg::PoseStamped ¤t_pose) override |
| Checks if the robot has moved compare to previous pose. More... | |
Public Member Functions inherited from nav2_controller::SimpleProgressChecker | |
| void | initialize (const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &plugin_name) override |
| Initialize parameters for ProgressChecker. More... | |
| bool | check (geometry_msgs::msg::PoseStamped ¤t_pose) override |
| Checks if the robot has moved compare to previous pose. More... | |
| void | reset () override |
| Reset class state upon calling. | |
Protected Member Functions | |
| bool | isRobotMovedEnough (const geometry_msgs::msg::Pose2D &pose) |
| Calculates robots movement from baseline pose. More... | |
| rcl_interfaces::msg::SetParametersResult | dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters) |
| Callback executed when a paramter change is detected. More... | |
Protected Member Functions inherited from nav2_controller::SimpleProgressChecker | |
| bool | isRobotMovedEnough (const geometry_msgs::msg::Pose2D &pose) |
| Calculates robots movement from baseline pose. More... | |
| void | resetBaselinePose (const geometry_msgs::msg::Pose2D &pose) |
| Resets baseline pose with the current pose of the robot. More... | |
| rcl_interfaces::msg::SetParametersResult | dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters) |
| Callback executed when a paramter change is detected. More... | |
Static Protected Member Functions | |
| static double | poseAngleDistance (const geometry_msgs::msg::Pose2D &, const geometry_msgs::msg::Pose2D &) |
Static Protected Member Functions inherited from nav2_controller::SimpleProgressChecker | |
| static double | pose_distance (const geometry_msgs::msg::Pose2D &, const geometry_msgs::msg::Pose2D &) |
Protected Attributes | |
| double | required_movement_angle_ |
| rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr | dyn_params_handler_ |
| std::string | plugin_name_ |
Protected Attributes inherited from nav2_controller::SimpleProgressChecker | |
| rclcpp::Clock::SharedPtr | clock_ |
| double | radius_ |
| rclcpp::Duration | time_allowance_ {0, 0} |
| geometry_msgs::msg::Pose2D | baseline_pose_ |
| rclcpp::Time | baseline_time_ |
| bool | baseline_pose_set_ {false} |
| rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr | dyn_params_handler_ |
| std::string | plugin_name_ |
Additional Inherited Members | |
Public Types inherited from nav2_core::ProgressChecker | |
| typedef std::shared_ptr< nav2_core::ProgressChecker > | Ptr |
This plugin is used to check the position and the angle of the robot to make sure that it is actually progressing or rotating towards a goal.
Definition at line 32 of file pose_progress_checker.hpp.
|
overridevirtual |
Checks if the robot has moved compare to previous pose.
| current_pose | Current pose of the robot |
Implements nav2_core::ProgressChecker.
Definition at line 50 of file pose_progress_checker.cpp.
References isRobotMovedEnough(), and nav2_controller::SimpleProgressChecker::resetBaselinePose().

|
protected |
Callback executed when a paramter change is detected.
| parameters | list of changed parameters |
Definition at line 78 of file pose_progress_checker.cpp.
Referenced by initialize().

|
overridevirtual |
Initialize parameters for ProgressChecker.
| parent | Node pointer |
Implements nav2_core::ProgressChecker.
Definition at line 33 of file pose_progress_checker.cpp.
References dynamicParametersCallback(), and nav2_controller::SimpleProgressChecker::initialize().

|
protected |
Calculates robots movement from baseline pose.
| pose | Current pose of the robot |
Definition at line 64 of file pose_progress_checker.cpp.
Referenced by check().
