10#ifndef _WAYPOINT_ACTION_HPP
11#define _WAYPOINT_ACTION_HPP
13#include <planner_msgs/action/pdla.hpp>
14#include <rclcpp/rclcpp.hpp>
15#include <std_msgs/msg/string.hpp>
32 const std::string & name,
const BT::NodeConfig & config,
33 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr logger_pub,
34 rclcpp::Node::SharedPtr ros_node);
38 bool setGoal(
typename Action::Goal & goal)
override;
42 void onFeedback(
const std::shared_ptr<const Feedback> feedback)
override;
45 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr logger_pub_;
Template for ROS2 Action with Behavior Tree.
Definition: ros_action_node.hpp:28
typename rclcpp_action::ClientGoalHandle< Action >::WrappedResult WrappedResult
Definition: ros_action_node.hpp:33
Waypoint Action Client implementation using the CUSTOM RosActionNode template.
Definition: waypoint_action.hpp:26
BT::NodeStatus onResult(const WrappedResult &wr) override
Definition: waypoint_action.cpp:47
void onFeedback(const std::shared_ptr< const Feedback > feedback) override
Definition: waypoint_action.cpp:58
bool setGoal(typename Action::Goal &goal) override
Configures the Goal message.
Definition: waypoint_action.cpp:32
static BT::PortsList providedPorts()
Definition: waypoint_action.cpp:24
Abstract class for ROS2 Action client with Behavior Tree.