Template for ROS2 Action with Behavior Tree. More...
#include <ros_action_node.hpp>
Inheritance diagram for behavior_tree::RosActionNode< ActionT >:
Collaboration diagram for behavior_tree::RosActionNode< ActionT >:Public Types | |
| using | Action = ActionT |
| 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 | |
| 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. | |
Protected Attributes | |
| 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_ |
Template for ROS2 Action with Behavior Tree.
| ActionT | Action Type |
behaviortree_ros2パッケージが動かなかったので,自作
| using behavior_tree::RosActionNode< ActionT >::Action = ActionT |
| using behavior_tree::RosActionNode< ActionT >::ActionClient = rclcpp_action::Client<Action> |
| using behavior_tree::RosActionNode< ActionT >::Feedback = typename Action::Feedback |
| using behavior_tree::RosActionNode< ActionT >::GoalHandle = rclcpp_action::ClientGoalHandle<Action> |
| using behavior_tree::RosActionNode< ActionT >::WrappedResult = typename rclcpp_action::ClientGoalHandle<Action>::WrappedResult |
| behavior_tree::RosActionNode< ActionT >::RosActionNode | ( | const std::string & | name, |
| const BT::NodeConfig & | config, | ||
| rclcpp::Node::SharedPtr | ros_node | ||
| ) |
Create action client.
| name | Node name |
| config | Node config |
| ros_node | pointer of ros node |
Get action_name from xml, and then create action client
|
virtual |
Behavior when recieving feadback.
|
override |
Cancels the currently active goal if one exists.
|
pure virtual |
Processes the final result received from the server.
| wr | The wrapped result containing the result code and data |
|
override |
This method manages the asynchronous state machine:
Checks if the result has been received.
|
override |
Called when the node is first ticked. Initiates the ROS 2 action.
Checks server availability, configures the goal using the derived class's setGoal, and sends the goal asynchronously.
|
pure virtual |
Configures the Goal message.
| goal | The Goal object to be sent to the server |
Implemented in behavior_tree::FindPingerAction, behavior_tree::QrAction, behavior_tree::FibonacciAction, and behavior_tree::WaypointAction.
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |