Template Class BtActionNode

Inheritance Relationships

Base Type

  • public BT::ActionNodeBase

Class Documentation

template<class ActionT>
class BtActionNode : public BT::ActionNodeBase

Abstract class representing an action based BT node.

Note

This is an Asynchronous (long-running) node which may return a RUNNING state while executing. It will re-initialize when halted.

Template Parameters:

ActionT – Type of action

Public Functions

inline BtActionNode(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfig &conf)

A plansys2::BtActionNode constructor.

Parameters:
  • xml_tag_name – Name for the XML tag for this node

  • action_nameAction name this node creates a client for

  • conf – BT node configuration

BtActionNode() = delete
inline virtual ~BtActionNode()
inline bool createActionClient(const std::string &action_name)

Create instance of an action client.

Parameters:

action_nameAction name to create client for

inline virtual BT::NodeStatus on_tick()

Function to perform some user-defined operation on tick Could do dynamic checks, such as getting updates to values on the blackboard.

inline virtual void on_feedback(const std::shared_ptr<const typename ActionT::Feedback> feedback)

Provides the opportunity for derived classes to log feedback, update the goal, or cancel the goal.

Parameters:

feedback – The feedback received from the action server

inline 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.

Returns:

BT::NodeStatus Returns SUCCESS by default, user may override return another value

inline virtual BT::NodeStatus on_aborted()

Function to perform some user-defined operation when the action is aborted.

Returns:

BT::NodeStatus Returns FAILURE by default, user may override return another value

inline virtual BT::NodeStatus on_cancelled()

Function to perform some user-defined operation when the action is cancelled.

Returns:

BT::NodeStatus Returns SUCCESS by default, user may override return another value

inline BT::NodeStatus tick() override

The main override required by a BT action.

Returns:

BT::NodeStatus Status of tick execution

inline 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.

Public Static Functions

static inline BT::PortsList providedBasicPorts(BT::PortsList addition)

Any subclass of BtActionNode that accepts parameters must provide a providedPorts method and call providedBasicPorts in it.

Parameters:

addition – Additional ports to add to BT port list

Returns:

BT::PortsList Containing basic ports along with node-specific ports

static inline BT::PortsList providedPorts()

Creates list of BT ports.

Returns:

BT::PortsList Containing basic ports along with node-specific ports

Protected Functions

inline void cancel_goal()

Function to cancel the current goal.

inline bool should_cancel_goal()

Function to check if current goal should be cancelled.

Returns:

bool True if current goal should be cancelled, false otherwise

inline void on_new_goal_received()

Function to send a new goal to the action server.

inline bool is_future_goal_handle_complete(std::chrono::milliseconds &elapsed)

Function to check if the action server acknowledged a new goal.

Parameters:

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.

Returns:

boolean True if future_goal_handle_ returns SUCCESS, False otherwise

inline void increment_recovery_count()

Function to increment recovery count on blackboard if this node wraps a recovery.

Protected Attributes

std::string action_name_
std::shared_ptr<rclcpp_action::Client<ActionT>> action_client_
ActionT::Goal goal_
bool goal_updated_ = {false}
bool goal_result_available_ = {false}
std::shared_ptr<std::shared_future<typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr>> future_goal_handle_
std::shared_future<typename ActionT::Impl::CancelGoalService::Response::SharedPtr> future_cancel_handle_
rclcpp::Time goal_sent_ts_
rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr goal_handle_
rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult result_
rclcpp_lifecycle::LifecycleNode::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_
int state_ = {IDLE}

Protected Static Attributes

static const int IDLE = 0
static const int GOAL_SENT = 1
static const int GOAL_EXECUTING = 2
static const int GOAL_FINISHING = 3
static const int GOAL_CANCELLING = 4
static const int GOAL_FINISHED = 5
static const int GOAL_FAILURE = 6