Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
A nav2_behavior_tree::BtActionNode class that wraps nav2_msgs::action::FollowPath. More...
#include <nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/follow_path_action.hpp>
Public Member Functions | |
FollowPathAction (const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf) | |
A constructor for nav2_behavior_tree::FollowPathAction. More... | |
void | on_tick () override |
Function to perform some user-defined operation on tick. | |
void | on_wait_for_result (std::shared_ptr< const nav2_msgs::action::FollowPath::Feedback > feedback) override |
Function to perform some user-defined operation after a timeout waiting for a result that hasn't been received yet. More... | |
![]() | |
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_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... | |
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 | providedPorts () |
Creates list of BT ports. More... | |
![]() | |
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... | |
Additional Inherited Members | |
![]() | |
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. | |
![]() | |
std::string | action_name_ |
std::shared_ptr< rclcpp_action::Client< nav2_msgs::action::FollowPath > > | action_client_ |
ActionT::Goal | goal_ |
bool | goal_updated_ |
bool | goal_result_available_ |
rclcpp_action::ClientGoalHandle< nav2_msgs::action::FollowPath >::SharedPtr | goal_handle_ |
rclcpp_action::ClientGoalHandle< nav2_msgs::action::FollowPath >::WrappedResult | result_ |
std::shared_ptr< const typename ActionT::Feedback > | feedback_ |
rclcpp::Node::SharedPtr | node_ |
rclcpp::CallbackGroup::SharedPtr | callback_group_ |
rclcpp::executors::SingleThreadedExecutor | callback_group_executor_ |
std::chrono::milliseconds | server_timeout_ |
std::chrono::milliseconds | max_timeout_ |
std::chrono::milliseconds | wait_for_service_timeout_ |
std::shared_ptr< std::shared_future< typename rclcpp_action::ClientGoalHandle< nav2_msgs::action::FollowPath >::SharedPtr > > | future_goal_handle_ |
rclcpp::Time | time_goal_sent_ |
bool | should_send_goal_ |
A nav2_behavior_tree::BtActionNode class that wraps nav2_msgs::action::FollowPath.
Definition at line 30 of file follow_path_action.hpp.
nav2_behavior_tree::FollowPathAction::FollowPathAction | ( | const std::string & | xml_tag_name, |
const std::string & | action_name, | ||
const BT::NodeConfiguration & | conf | ||
) |
A constructor for nav2_behavior_tree::FollowPathAction.
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 23 of file follow_path_action.cpp.
|
override |
Function to perform some user-defined operation after a timeout waiting for a result that hasn't been received yet.
feedback | shared_ptr to latest feedback message |
Definition at line 38 of file follow_path_action.cpp.
|
inlinestatic |
Creates list of BT ports.
Definition at line 61 of file follow_path_action.hpp.
References nav2_behavior_tree::BtActionNode< nav2_msgs::action::FollowPath >::providedBasicPorts().