Calls an action server that uses nav2_msgs::action::NavigateThroughPoses and outputs feedback The NavigateThroughPoses action (ROS 2 Humble) does not produce a result.
More...
|
| NavigateThroughPosesAction (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) |
| Constructor for NavigateThroughPosesAction behavior.
|
|
| NavigateThroughPosesAction (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase > client_interface) |
| Overload for constructor which allows providing an alternate action client interface – useful for unit testing, but not a requirement.
|
|
tl::expected< std::string, std::string > | getActionName () override |
| Gets the name of the action to use when initializing the action client.
|
|
| ActionClientBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) |
| Constructs ActionClientBehaviorBase using the RclcppClientInterface.
|
|
| ActionClientBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase > client_interface) |
| Constructs ActionClientBehaviorBase using a user-provided implementation of ClientInterfaceBase.
|
|
virtual | ~ActionClientBehaviorBase ()=default |
|
| AsyncBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) |
|
virtual | ~AsyncBehaviorBase ()=default |
|
BT::NodeStatus | onStart () override |
| Required implementation of BT::StatefulActionNode::onStart().
|
|
BT::NodeStatus | onRunning () override |
| Required implementation of BT::StatefulActionNode::onRunning().
|
|
void | onHalted () override |
| Required implementation of BT::StatefulActionNode::onHalted().
|
|
void | resetStatus () |
| Resets the internal status of this node.
|
|
| SharedResourcesNode (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) |
| Constructor for SharedResourcesNode. Called by BT::BehaviorTreeFactory when creating a new behavior tree containing this node.
|
|
|
using | ClientGoalHandle = rclcpp_action::ClientGoalHandle< NavigateThroughPoses > |
|
virtual tl::expected< bool, std::string > | processResult (const std::shared_ptr< typename ActionT::Result >) |
| Optional user-provided function to process the action result after the action has finished.
|
|
virtual void | processFeedback (const std::shared_ptr< const typename ActionT::Feedback >) |
| Optional user-provided function to process feedback sent by the action server.
|
|
virtual std::string | getAbortedMessage (const std::shared_ptr< const typename ActionT::Result >) const |
| Optional user-provided function to retrieve and surface an error message from an aborted action server result.
|
|
void | notifyCanHalt () |
| Called when runAsync() finishes to notify onHalted() that the async process has finished.
|
|
std::shared_ptr< BehaviorContext > | shared_resources_ |
|
Calls an action server that uses nav2_msgs::action::NavigateThroughPoses and outputs feedback The NavigateThroughPoses action (ROS 2 Humble) does not produce a result.
Data Port Name | Port Type | Object Type |
action_name | Input | std::string |
behavior_tree_path | Input | std::string |
poses | Input | std::vector<geometry_msgs::msg::PoseStamped> |
timeout_sec | Input | double |
current_pose | Output | geometry_msgs::msg::PoseStamped |
navigation_time | Output | builtin_interfaces::msg::Duration |
estimated_time_remaining | Output | builtin_interfaces::msg::Duration |
number_of_recoveries | Output | int16_t |
distance_remaining | Output | float |
number_of_poses_remaining | Output | int16 |