Nav2 Navigation Stack - rolling
main
ROS 2 Navigation Stack
|
Goal Checker plugin that checks the position difference and velocity. More...
#include <nav2_controller/include/nav2_controller/plugins/stopped_goal_checker.hpp>
Public Member Functions | |
void | initialize (const nav2::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... | |
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... | |
![]() | |
void | reset () override |
Protected Member Functions | |
rcl_interfaces::msg::SetParametersResult | dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters) |
Callback executed when a parameter change is detected. More... | |
![]() | |
rcl_interfaces::msg::SetParametersResult | dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters) |
Callback executed when a parameter change is detected. More... | |
Protected Attributes | |
double | rot_stopped_velocity_ |
double | trans_stopped_velocity_ |
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr | dyn_params_handler_ |
std::string | plugin_name_ |
![]() | |
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 | |
![]() | |
typedef std::shared_ptr< nav2_core::GoalChecker > | Ptr |
Goal Checker plugin that checks the position difference and velocity.
Definition at line 53 of file stopped_goal_checker.hpp.
|
protected |
Callback executed when a parameter change is detected.
parameters | list of changed parameters |
Definition at line 118 of file stopped_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 |
Reimplemented from nav2_controller::SimpleGoalChecker.
Definition at line 96 of file stopped_goal_checker.cpp.
|
overridevirtual |
Initialize any parameters from the NodeHandle.
parent | Node pointer for grabbing parameters |
Reimplemented from nav2_controller::SimpleGoalChecker.
Definition at line 58 of file stopped_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 |
Reimplemented from nav2_controller::SimpleGoalChecker.
Definition at line 83 of file stopped_goal_checker.cpp.