Common
common packages for kyubic
 
Loading...
Searching...
No Matches
behavior_tree::WrenchAction Class Reference

Behavior Tree node for the Wrench Action. More...

#include <wrench_action.hpp>

+ Inheritance diagram for behavior_tree::WrenchAction:
+ Collaboration diagram for behavior_tree::WrenchAction:

Public Types

using Goal = wrench_action_sample_msgs::action::Wrench::Goal
 
- Public Types inherited from behavior_tree::RosActionNode< wrench_action_sample_msgs::action::Wrench >
using Action = wrench_action_sample_msgs::action::Wrench
 
using GoalHandle = rclcpp_action::ClientGoalHandle< Action >
 
using ActionClient = rclcpp_action::Client< Action >
 
using WrappedResult = typename rclcpp_action::ClientGoalHandle< Action >::WrappedResult
 
using Feedback = typename Action::Feedback
 

Public Member Functions

 WrenchAction (const std::string &name, const BT::NodeConfig &config, rclcpp::Node::SharedPtr ros_node)
 Constructor for the WrenchAction node.
 
bool setGoal (Goal &goal) override
 Configures the Goal message before sending it to the server.
 
BT::NodeStatus onResult (const WrappedResult &wr) override
 callback executed when the action result is received.
 
- Public Member Functions inherited from behavior_tree::RosActionNode< wrench_action_sample_msgs::action::Wrench >
 RosActionNode (const std::string &name, const BT::NodeConfig &config, rclcpp::Node::SharedPtr ros_node)
 Create action client.
 
virtual bool setGoal (typename Action::Goal &goal)=0
 Configures the Goal message.
 
virtual BT::NodeStatus onResult (const WrappedResult &wr)=0
 Processes the final result received from the server.
 
virtual void onFeedback (const std::shared_ptr< const Feedback > feedback)
 Behavior when recieving feadback.
 
BT::NodeStatus onStart () override
 Called when the node is first ticked. Initiates the ROS 2 action.
 
BT::NodeStatus onRunning () override
 This method manages the asynchronous state machine:
 
void onHalted () override
 Cancels the currently active goal if one exists.
 

Static Public Member Functions

static BT::PortsList providedPorts ()
 Defines the input and output ports for this node.
 

Additional Inherited Members

- Protected Attributes inherited from behavior_tree::RosActionNode< wrench_action_sample_msgs::action::Wrench >
rclcpp::Node::SharedPtr ros_node_
 
ActionClient::SharedPtr client_
 
std::string action_name
 
std::shared_future< typename GoalHandle::SharedPtr > future_goal_handle_
 
std::shared_future< WrappedResultfuture_result_
 
GoalHandle::SharedPtr active_goal_handle_
 

Detailed Description

Behavior Tree node for the Wrench Action.

Send the WrenchStamped Topic for the specified period. If the action completes successfully, it returns SUCCESS.

Member Typedef Documentation

◆ Goal

using behavior_tree::WrenchAction::Goal = wrench_action_sample_msgs::action::Wrench::Goal

Constructor & Destructor Documentation

◆ WrenchAction()

behavior_tree::WrenchAction::WrenchAction ( const std::string &  name,
const BT::NodeConfig &  config,
rclcpp::Node::SharedPtr  ros_node 
)

Constructor for the WrenchAction node.

Parameters
nameThe name of the node in the behavior tree.
configThe node configuration.
ros_nodeShared pointer to the ROS 2 node used for communication.

Member Function Documentation

◆ onResult()

BT::NodeStatus behavior_tree::WrenchAction::onResult ( const WrappedResult wr)
override

callback executed when the action result is received.

Parameters
wrThe wrapped result containing the status code and the result data.
Returns
BT::NodeStatus::SUCCESS if the action succeeded, BT::NodeStatus::FAILURE otherwise.

◆ providedPorts()

BT::PortsList behavior_tree::WrenchAction::providedPorts ( )
static

Defines the input and output ports for this node.

Returns
A list containing:
  • InputPort "action_name": Name of the action server.
  • InputPort "duration_sec": Duration to apply the wrench (in seconds).
  • OutputPort "total_updates": The total number of updates received from the server.

◆ setGoal()

bool behavior_tree::WrenchAction::setGoal ( Goal goal)
override

Configures the Goal message before sending it to the server.

Parameters
goalThe goal object to be populated.
Returns
true if the goal was set successfully, false if the input port is missing.

The documentation for this class was generated from the following files: