![]() |
AutoAPMS
Streamlining behaviors in ROS 2
|
Generic behavior tree node wrapper for a ROS 2 action client. More...
#include <auto_apms_behavior_tree_core/node/ros_action_node.hpp>
Public Member Functions | |
| RosActionNode (const std::string &instance_name, const Config &config, Context context) | |
| Constructor. | |
| virtual void | onHalt () |
| Callback invoked when the node is halted by the behavior tree. | |
| virtual bool | setGoal (Goal &goal) |
| Set the goal message to be sent to the ROS 2 action. | |
| virtual BT::NodeStatus | onResultReceived (const WrappedResult &result) |
| Callback invoked after the result that is sent by the action server when the goal terminated was received. | |
| virtual BT::NodeStatus | onFeedback (const Feedback &feedback) |
| Callback invoked after action feedback was received. | |
| virtual BT::NodeStatus | onFailure (ActionNodeErrorCode error) |
| Callback invoked when one of the errors in ActionNodeErrorCode occur. | |
| void | cancelGoal () |
| Synchronous method that sends a request to the server to cancel the current action. | |
| bool | createClient (const std::string &action_name) |
| Create the client of the ROS 2 action. | |
| std::string | getActionName () const |
| Get the name of the action this node connects with. | |
Static Public Member Functions | |
| static BT::PortsList | providedBasicPorts (BT::PortsList addition) |
| Derived nodes implementing the static method RosActionNode::providedPorts may call this method to also include the default port for ROS 2 behavior tree nodes. | |
| static BT::PortsList | providedPorts () |
| If a behavior tree requires input/output data ports, the developer must define this method accordingly. | |
Generic behavior tree node wrapper for a ROS 2 action client.
When ticked, this node sends an action goal and awaits the execution result asynchronously. When halted, the node blocks until both the action was cancelled and the result was received. Inheriting classes must reimplement the virtual methods as described below.
By default, the name of the action will be determined as follows:
topic, use that.It is possible to customize which port is used to determine the action name and also extend the input's value with a prefix or suffix. This is achieved by including the special pattern (input:<port_name>) in NodeRegistrationOptions::topic and replacing <port_name> with the desired input port name.
Example: Given the user implements an input port BT::InputPort<std::string>("my_port"), one may create a client for the action "foo/bar" by defining NodeRegistrationOptions::topic as (input:my_port)/bar and providing the string "foo" to the port with name my_port.
Additionally, the following characteristics depend on NodeRegistrationOptions:
true, a warning is logged. Otherwise, an exception is raised.| ActionT | Type of the ROS 2 action. |
Definition at line 98 of file ros_action_node.hpp.
|
inlineexplicit |
Constructor.
Derived nodes are automatically created by TreeBuilder::instantiate when included inside a node manifest associated with the behavior tree resource.
| instance_name | Name given to this specific node instance. |
| config | Structure of internal data determined at runtime by BT::BehaviorTreeFactory. |
| context | Additional parameters specific to ROS 2 determined at runtime by TreeBuilder. |
Definition at line 272 of file ros_action_node.hpp.
|
inlinestatic |
Derived nodes implementing the static method RosActionNode::providedPorts may call this method to also include the default port for ROS 2 behavior tree nodes.
| addition | Additional ports to add to the ports list. |
Definition at line 143 of file ros_action_node.hpp.
|
inlinestatic |
If a behavior tree requires input/output data ports, the developer must define this method accordingly.
Definition at line 154 of file ros_action_node.hpp.
|
inlinevirtual |
Callback invoked when the node is halted by the behavior tree.
Afterwards, the ROS 2 action will be cancelled.
By default, this callback does nothing.
Definition at line 291 of file ros_action_node.hpp.
|
inlinevirtual |
Set the goal message to be sent to the ROS 2 action.
The node may deny to send a goal by returning false. Otherwise, this method should return true.
By default, this callback always returns true.
| goal | Reference to the goal message. |
false if the request should not be sent. In that case, onFailure(INVALID_GOAL) will be called. Definition at line 296 of file ros_action_node.hpp.
|
inlinevirtual |
Callback invoked after the result that is sent by the action server when the goal terminated was received.
Based on the result message, the node may return BT::NodeStatus::SUCCESS or BT::NodeStatus::FAILURE.
By default, this callback returns BT::NodeStatus::SUCCESS if the action finished or was canceled successfully. Otherwise it returns BT::NodeStatus::FAILURE.
| result | Reference to the result message. |
Definition at line 302 of file ros_action_node.hpp.
|
inlinevirtual |
Callback invoked after action feedback was received.
The node may cancel the current action by returning BT::NodeStatus::SUCCESS or BT::NodeStatus::FAILURE. Otherwise, this should return BT::NodeStatus::RUNNING to indicate that the action should continue.
By default, this callback always returns BT::NodeStatus::RUNNING.
| feedback | Received feedback message. |
Definition at line 328 of file ros_action_node.hpp.
|
inlinevirtual |
Callback invoked when one of the errors in ActionNodeErrorCode occur.
Based on the error code, the node may return BT::NodeStatus::SUCCESS or BT::NodeStatus::FAILURE.
By default, this callback throws auto_apms_behavior_tree::exceptions::RosNodeError and interrupts the tree.
| error | Code for the error that has occurred. |
Definition at line 334 of file ros_action_node.hpp.
|
inline |
Synchronous method that sends a request to the server to cancel the current action.
This method returns as soon as the action is successfully cancelled or an error occurred in the process.
Definition at line 343 of file ros_action_node.hpp.
|
inline |
Create the client of the ROS 2 action.
| action_name | Name of the action. |
true if the client was created successfully, false otherwise. Definition at line 617 of file ros_action_node.hpp.
|
inline |
Get the name of the action this node connects with.
Definition at line 677 of file ros_action_node.hpp.