AutoAPMS
Resilient Robot Mission Management
|
#include <auto_apms_behavior_tree/node/ros_action_node.hpp>
Public Types | |
using | ActionType = ActionT |
using | Goal = typename ActionT::Goal |
using | Feedback = typename ActionT::Feedback |
using | WrappedResult = typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult |
using | Config = BT::NodeConfig |
using | Context = RosNodeContext |
Public Member Functions | |
RosActionNode (const std::string &instance_name, const Config &config, const Context &context) | |
virtual | ~RosActionNode ()=default |
virtual void | onHalt () |
virtual bool | setGoal (Goal &goal) |
virtual BT::NodeStatus | onResultReceived (const WrappedResult &result) |
virtual BT::NodeStatus | onFeedback (const std::shared_ptr< const Feedback > feedback_ptr) |
virtual BT::NodeStatus | onFailure (ActionNodeErrorCode error) |
void | cancelGoal () |
void | halt () override |
BT::NodeStatus | tick () override |
void | setActionName (const std::string &action_name) |
std::string | getFullName () const |
Static Public Member Functions | |
static BT::PortsList | providedBasicPorts (BT::PortsList addition) |
static BT::PortsList | providedPorts () |
Protected Member Functions | |
const Context & | getRosContext () |
Static Protected Member Functions | |
static std::mutex & | getMutex () |
static ClientsRegistry & | getRegistry () |
Protected Attributes | |
const rclcpp::Logger | logger_ |
Abstract class to wrap rclcpp_action::Client<>
For instance, given the type AddTwoInts described in this tutorial: https://docs.ros.org/en/humble/Tutorials/Intermediate/Writing-an-Action-Server-Client/Cpp.html
the corresponding wrapper would be:
class FibonacciNode: public RosActionNode<action_tutorials_interfaces::action::Fibonacci>
RosActionNode will try to be non-blocking for the entire duration of the call. The derived class must reimplement the virtual methods as described below.
The name of the action will be determined as follows:
Definition at line 73 of file ros_action_node.hpp.
using ActionType = ActionT |
Definition at line 92 of file ros_action_node.hpp.
using Goal = typename ActionT::Goal |
Definition at line 93 of file ros_action_node.hpp.
using Feedback = typename ActionT::Feedback |
Definition at line 94 of file ros_action_node.hpp.
using WrappedResult = typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult |
Definition at line 95 of file ros_action_node.hpp.
using Config = BT::NodeConfig |
Definition at line 96 of file ros_action_node.hpp.
using Context = RosNodeContext |
Definition at line 97 of file ros_action_node.hpp.
|
inlineexplicit |
Definition at line 209 of file ros_action_node.hpp.
|
virtualdefault |
|
inlinestatic |
Any subclass of RosActionNode that has ports must implement a providedPorts method and call providedBasicPorts in it.
addition | Additional ports to add to BT port list |
Definition at line 110 of file ros_action_node.hpp.
|
inlinestatic |
Creates list of BT ports.
Definition at line 121 of file ros_action_node.hpp.
|
inlinevirtual |
Callback executed when the node is halted. Note that cancelGoal() is done automatically.
Definition at line 285 of file ros_action_node.hpp.
|
inlinevirtual |
setGoal s a callback that allows the user to set the goal message (ActionT::Goal).
goal | the goal to be sent to the action server. |
Definition at line 290 of file ros_action_node.hpp.
|
inlinevirtual |
Callback invoked when the result is received by the server. It is up to the user to define if the action returns SUCCESS or FAILURE.
Definition at line 296 of file ros_action_node.hpp.
|
inlinevirtual |
Callback invoked when the feedback is received. It generally returns RUNNING, but the user can also use this callback to cancel the current action and return SUCCESS or FAILURE.
Definition at line 304 of file ros_action_node.hpp.
|
inlinevirtual |
Callback invoked when something goes wrong. It must return either SUCCESS or FAILURE.
Definition at line 310 of file ros_action_node.hpp.
|
inline |
Method used to send a request to the Action server to cancel the current goal.
Wait for the cancellation to be complete
Definition at line 317 of file ros_action_node.hpp.
|
inlineoverride |
The default halt() implementation will call cancelGoal if necessary.
Definition at line 351 of file ros_action_node.hpp.
|
inlineoverride |
Definition at line 361 of file ros_action_node.hpp.
|
inline |
Can be used to change the name of the action programmatically.
Definition at line 500 of file ros_action_node.hpp.
|
inline |
Definition at line 507 of file ros_action_node.hpp.
|
inlineprotected |
Definition at line 519 of file ros_action_node.hpp.
|
inlinestaticprotected |
Definition at line 525 of file ros_action_node.hpp.
|
inlinestaticprotected |
Definition at line 532 of file ros_action_node.hpp.
|
protected |
Definition at line 177 of file ros_action_node.hpp.