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< WrappedResult > | future_result_ |
| GoalHandle::SharedPtr | active_goal_handle_ |
Behavior Tree node for the Wrench Action.
Send the WrenchStamped Topic for the specified period. If the action completes successfully, it returns SUCCESS.
| using behavior_tree::WrenchAction::Goal = wrench_action_sample_msgs::action::Wrench::Goal |
| behavior_tree::WrenchAction::WrenchAction | ( | const std::string & | name, |
| const BT::NodeConfig & | config, | ||
| rclcpp::Node::SharedPtr | ros_node | ||
| ) |
Constructor for the WrenchAction node.
| name | The name of the node in the behavior tree. |
| config | The node configuration. |
| ros_node | Shared pointer to the ROS 2 node used for communication. |
|
override |
callback executed when the action result is received.
| wr | The wrapped result containing the status code and the result data. |
|
static |
Defines the input and output ports for this node.
|
override |
Configures the Goal message before sending it to the server.
| goal | The goal object to be populated. |