Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_controller::SimpleGoalChecker Class Reference

Goal Checker plugin that only checks the position difference. More...

#include <nav2_controller/include/nav2_controller/plugins/simple_goal_checker.hpp>

Inheritance diagram for nav2_controller::SimpleGoalChecker:
Inheritance graph
[legend]
Collaboration diagram for nav2_controller::SimpleGoalChecker:
Collaboration graph
[legend]

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...
 

Protected Attributes

double xy_goal_tolerance_
 
double yaw_goal_tolerance_
 
bool stateful_
 
bool check_xy_
 
double xy_goal_tolerance_sq_
 
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
 
std::string plugin_name_
 

Additional Inherited Members

- Public Types inherited from nav2_core::GoalChecker
typedef std::shared_ptr< nav2_core::GoalCheckerPtr
 

Detailed Description

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.

Member Function Documentation

◆ dynamicParametersCallback()

rcl_interfaces::msg::SetParametersResult nav2_controller::SimpleGoalChecker::dynamicParametersCallback ( std::vector< rclcpp::Parameter >  parameters)
protected

Callback executed when a parameter change is detected.

Parameters
parameterslist of changed parameters

Definition at line 144 of file simple_goal_checker.cpp.

◆ getTolerances()

bool nav2_controller::SimpleGoalChecker::getTolerances ( geometry_msgs::msg::Pose &  pose_tolerance,
geometry_msgs::msg::Twist &  vel_tolerance 
)
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).

Parameters
pose_toleranceThe tolerance used for checking in Pose fields
vel_toleranceThe tolerance used for checking velocity fields
Returns
True if the tolerances are valid to use

Implements nav2_core::GoalChecker.

Reimplemented in nav2_controller::StoppedGoalChecker.

Definition at line 120 of file simple_goal_checker.cpp.

◆ initialize()

void nav2_controller::SimpleGoalChecker::initialize ( const rclcpp_lifecycle::LifecycleNode::WeakPtr &  parent,
const std::string &  plugin_name,
const std::shared_ptr< nav2_costmap_2d::Costmap2DROS costmap_ros 
)
overridevirtual

Initialize any parameters from the NodeHandle.

Parameters
parentNode pointer for grabbing parameters

Implements nav2_core::GoalChecker.

Reimplemented in nav2_controller::StoppedGoalChecker.

Definition at line 64 of file simple_goal_checker.cpp.

◆ isGoalReached()

bool nav2_controller::SimpleGoalChecker::isGoalReached ( const geometry_msgs::msg::Pose &  query_pose,
const geometry_msgs::msg::Pose &  goal_pose,
const geometry_msgs::msg::Twist &  velocity 
)
overridevirtual

Check whether the goal should be considered reached.

Parameters
query_poseThe pose to check
goal_poseThe pose to check against
velocityThe robot's current velocity
Returns
True if goal is reached

Implements nav2_core::GoalChecker.

Reimplemented in nav2_controller::StoppedGoalChecker.

Definition at line 98 of file simple_goal_checker.cpp.


The documentation for this class was generated from the following files: