Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
Abstract class representing an action based BT node. More...
#include <nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp>
Public Member Functions | |
BtActionNode (const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf) | |
A nav2_behavior_tree::BtActionNode constructor. More... | |
void | createActionClient (const std::string &action_name) |
Create instance of an action client. More... | |
virtual void | on_tick () |
Function to perform some user-defined operation on tick Could do dynamic checks, such as getting updates to values on the blackboard. | |
virtual void | on_wait_for_result (std::shared_ptr< const typename ActionT::Feedback >) |
Function to perform some user-defined operation after a timeout waiting for a result that hasn't been received yet. Also provides access to the latest feedback message from the action server. Feedback will be nullptr in subsequent calls to this function if no new feedback is received while waiting for a result. More... | |
virtual BT::NodeStatus | on_success () |
Function to perform some user-defined operation upon successful completion of the action. Could put a value on the blackboard. More... | |
virtual BT::NodeStatus | on_aborted () |
Function to perform some user-defined operation when the action is aborted. More... | |
virtual BT::NodeStatus | on_cancelled () |
Function to perform some user-defined operation when the action is cancelled. More... | |
virtual void | on_timeout () |
Function to perform work in a BT Node when the action server times out Such as setting the error code ID status to timed out for action clients. | |
BT::NodeStatus | tick () override |
The main override required by a BT action. More... | |
void | halt () override |
The other (optional) override required by a BT action. In this case, we make sure to cancel the ROS2 action if it is still running. | |
Static Public Member Functions | |
static BT::PortsList | providedBasicPorts (BT::PortsList addition) |
Any subclass of BtActionNode that accepts parameters must provide a providedPorts method and call providedBasicPorts in it. More... | |
static BT::PortsList | providedPorts () |
Creates list of BT ports. More... | |
Protected Member Functions | |
bool | should_cancel_goal () |
Function to check if current goal should be cancelled. More... | |
void | send_new_goal () |
Function to send new goal to action server. | |
bool | is_future_goal_handle_complete (std::chrono::milliseconds &elapsed) |
Function to check if the action server acknowledged a new goal. More... | |
void | increment_recovery_count () |
Function to increment recovery count on blackboard if this node wraps a recovery. | |
Abstract class representing an action based BT node.
ActionT | Type of action |
Definition at line 41 of file bt_action_node.hpp.
|
inline |
A nav2_behavior_tree::BtActionNode constructor.
xml_tag_name | Name for the XML tag for this node |
action_name | Action name this node creates a client for |
conf | BT node configuration |
Definition at line 50 of file bt_action_node.hpp.
|
inline |
Create instance of an action client.
action_name | Action name to create client for |
Definition at line 96 of file bt_action_node.hpp.
|
inlineprotected |
Function to check if the action server acknowledged a new goal.
elapsed | Duration since the last goal was sent and future goal handle has not completed. After waiting for the future to complete, this value is incremented with the timeout value. |
Definition at line 424 of file bt_action_node.hpp.
|
inlinevirtual |
Function to perform some user-defined operation when the action is aborted.
Reimplemented in opennav_docking_bt::UndockRobotAction, opennav_docking_bt::DockRobotAction, nav2_behavior_tree::WaitAction, nav2_behavior_tree::SpinAction, nav2_behavior_tree::SmoothPathAction, nav2_behavior_tree::NavigateToPoseAction, nav2_behavior_tree::NavigateThroughPosesAction, nav2_behavior_tree::FollowPathAction, nav2_behavior_tree::DriveOnHeadingAction, nav2_behavior_tree::ComputeRouteAction, nav2_behavior_tree::ComputePathToPoseAction, nav2_behavior_tree::ComputePathThroughPosesAction, nav2_behavior_tree::ComputeAndTrackRouteAction, nav2_behavior_tree::BackUpAction, and nav2_behavior_tree::AssistedTeleopAction.
Definition at line 176 of file bt_action_node.hpp.
|
inlinevirtual |
Function to perform some user-defined operation when the action is cancelled.
Reimplemented in opennav_docking_bt::UndockRobotAction, opennav_docking_bt::DockRobotAction, nav2_behavior_tree::WaitAction, nav2_behavior_tree::SpinAction, nav2_behavior_tree::SmoothPathAction, nav2_behavior_tree::NavigateToPoseAction, nav2_behavior_tree::NavigateThroughPosesAction, nav2_behavior_tree::FollowPathAction, nav2_behavior_tree::DriveOnHeadingAction, nav2_behavior_tree::ComputeRouteAction, nav2_behavior_tree::ComputePathToPoseAction, nav2_behavior_tree::ComputePathThroughPosesAction, nav2_behavior_tree::ComputeAndTrackRouteAction, nav2_behavior_tree::BackUpAction, and nav2_behavior_tree::AssistedTeleopAction.
Definition at line 185 of file bt_action_node.hpp.
|
inlinevirtual |
Function to perform some user-defined operation upon successful completion of the action. Could put a value on the blackboard.
Reimplemented in opennav_docking_bt::UndockRobotAction, opennav_docking_bt::DockRobotAction, nav2_behavior_tree::WaitAction, nav2_behavior_tree::SpinAction, nav2_behavior_tree::SmoothPathAction, nav2_behavior_tree::NavigateToPoseAction, nav2_behavior_tree::NavigateThroughPosesAction, nav2_behavior_tree::FollowPathAction, nav2_behavior_tree::DriveOnHeadingAction, nav2_behavior_tree::ComputeRouteAction, nav2_behavior_tree::ComputePathToPoseAction, nav2_behavior_tree::ComputePathThroughPosesAction, nav2_behavior_tree::ComputeAndTrackRouteAction, nav2_behavior_tree::BackUpAction, and nav2_behavior_tree::AssistedTeleopAction.
Definition at line 167 of file bt_action_node.hpp.
|
inlinevirtual |
Function to perform some user-defined operation after a timeout waiting for a result that hasn't been received yet. Also provides access to the latest feedback message from the action server. Feedback will be nullptr in subsequent calls to this function if no new feedback is received while waiting for a result.
feedback | shared_ptr to latest feedback message, nullptr if no new feedback was received |
Definition at line 158 of file bt_action_node.hpp.
|
inlinestatic |
Any subclass of BtActionNode that accepts parameters must provide a providedPorts method and call providedBasicPorts in it.
addition | Additional ports to add to BT port list |
Definition at line 120 of file bt_action_node.hpp.
|
inlinestatic |
Creates list of BT ports.
Definition at line 135 of file bt_action_node.hpp.
|
inlineprotected |
Function to check if current goal should be cancelled.
Definition at line 359 of file bt_action_node.hpp.
|
inlineoverride |
The main override required by a BT action.
Definition at line 203 of file bt_action_node.hpp.