Nav2 Navigation Stack - rolling
main
ROS 2 Navigation Stack
|
This plugin is used to check the position of the robot to make sure that it is actually progressing towards a goal. More...
#include <nav2_controller/include/nav2_controller/plugins/simple_progress_checker.hpp>
Public Member Functions | |
void | initialize (const nav2::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::Pose &pose) |
Calculates robots movement from baseline pose. More... | |
void | resetBaselinePose (const geometry_msgs::msg::Pose &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 parameter change is detected. More... | |
Static Protected Member Functions | |
static double | pose_distance (const geometry_msgs::msg::Pose &, const geometry_msgs::msg::Pose &) |
Additional Inherited Members | |
![]() | |
typedef std::shared_ptr< nav2_core::ProgressChecker > | Ptr |
This plugin is used to check the position of the robot to make sure that it is actually progressing towards a goal.
Definition at line 34 of file simple_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 54 of file simple_progress_checker.cpp.
References isRobotMovedEnough(), and resetBaselinePose().
|
protected |
Callback executed when a parameter change is detected.
parameters | list of changed parameters |
Definition at line 93 of file simple_progress_checker.cpp.
Referenced by initialize().
|
overridevirtual |
Initialize parameters for ProgressChecker.
parent | Node pointer |
Implements nav2_core::ProgressChecker.
Definition at line 30 of file simple_progress_checker.cpp.
References dynamicParametersCallback().
Referenced by nav2_controller::PoseProgressChecker::initialize().
|
protected |
Calculates robots movement from baseline pose.
pose | Current pose of the robot |
Definition at line 77 of file simple_progress_checker.cpp.
Referenced by check().
|
protected |
Resets baseline pose with the current pose of the robot.
pose | Current pose of the robot |
Definition at line 70 of file simple_progress_checker.cpp.
Referenced by nav2_controller::PoseProgressChecker::check(), and check().