Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
Goal Checker plugin that only checks the position difference. More...
#include <nav2_controller/include/nav2_controller/plugins/simple_goal_checker.hpp>
Public Member Functions | |
void | initialize (const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &plugin_name, const std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override |
Initialize any parameters from the NodeHandle. More... | |
void | reset () override |
bool | isGoalReached (const geometry_msgs::msg::Pose &query_pose, const geometry_msgs::msg::Pose &goal_pose, const geometry_msgs::msg::Twist &velocity) override |
Check whether the goal should be considered reached. More... | |
bool | getTolerances (geometry_msgs::msg::Pose &pose_tolerance, geometry_msgs::msg::Twist &vel_tolerance) override |
Get the maximum possible tolerances used for goal checking in the major types. Any field without a valid entry is replaced with std::numeric_limits<double>::lowest() to indicate that it is not measured. For tolerance across multiple entries (e.x. XY tolerances), both fields will contain this value since it is the maximum tolerance that each independent field could be assuming the other has no error (e.x. X and Y). More... | |
Protected Member Functions | |
rcl_interfaces::msg::SetParametersResult | dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters) |
Callback executed when a parameter change is detected. More... | |
Additional Inherited Members | |
![]() | |
typedef std::shared_ptr< nav2_core::GoalChecker > | Ptr |
Goal Checker plugin that only checks the position difference.
This class can be stateful if the stateful parameter is set to true (which it is by default). This means that the goal checker will not check if the xy position matches again once it is found to be true.
Definition at line 57 of file simple_goal_checker.hpp.
|
protected |
Callback executed when a parameter change is detected.
parameters | list of changed parameters |
Definition at line 144 of file simple_goal_checker.cpp.
|
overridevirtual |
Get the maximum possible tolerances used for goal checking in the major types. Any field without a valid entry is replaced with std::numeric_limits<double>::lowest() to indicate that it is not measured. For tolerance across multiple entries (e.x. XY tolerances), both fields will contain this value since it is the maximum tolerance that each independent field could be assuming the other has no error (e.x. X and Y).
pose_tolerance | The tolerance used for checking in Pose fields |
vel_tolerance | The tolerance used for checking velocity fields |
Implements nav2_core::GoalChecker.
Reimplemented in nav2_controller::StoppedGoalChecker.
Definition at line 120 of file simple_goal_checker.cpp.
|
overridevirtual |
Initialize any parameters from the NodeHandle.
parent | Node pointer for grabbing parameters |
Implements nav2_core::GoalChecker.
Reimplemented in nav2_controller::StoppedGoalChecker.
Definition at line 64 of file simple_goal_checker.cpp.
|
overridevirtual |
Check whether the goal should be considered reached.
query_pose | The pose to check |
goal_pose | The pose to check against |
velocity | The robot's current velocity |
Implements nav2_core::GoalChecker.
Reimplemented in nav2_controller::StoppedGoalChecker.
Definition at line 98 of file simple_goal_checker.cpp.