1#ifndef _RESET_LOCALIZATION_HPP
2#define _RESET_LOCALIZATION_HPP
4#include <behaviortree_cpp/action_node.h>
6#include <localization_msgs/srv/reset.hpp>
7#include <rclcpp/rclcpp.hpp>
8#include <std_msgs/msg/string.hpp>
17 const std::string & name,
const BT::NodeConfig & config,
18 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr logger_pub,
19 rclcpp::Node::SharedPtr ros_node);
23 BT::NodeStatus
onStart()
override;
28 rclcpp::Node::SharedPtr ros_node_;
29 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr logger_pub_;
30 rclcpp::Client<localization_msgs::srv::Reset>::SharedPtr client_;
31 std::shared_future<localization_msgs::srv::Reset::Response::SharedPtr> future_response_;
32 std::string last_service_name_;
Definition: reset_localization.hpp:14
BT::NodeStatus onRunning() override
Definition: reset_localization.cpp:57
void onHalted() override
Definition: reset_localization.cpp:82
static BT::PortsList providedPorts()
Definition: reset_localization.cpp:13
BT::NodeStatus onStart() override
Definition: reset_localization.cpp:20