3#include <tf2/LinearMath/Matrix3x3.h>
4#include <tf2/LinearMath/Quaternion.h>
6#include <geometry_msgs/msg/twist_with_covariance_stamped.hpp>
7#include <nav_msgs/msg/odometry.hpp>
8#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
10#include "custom_interfaces/msg/vehicle_state.hpp"
11#include "fs_msgs/msg/finished_signal.hpp"
12#include "fs_msgs/msg/go_signal.hpp"
13#include "geometry_msgs/msg/transform_stamped.hpp"
14#include "pacsim/msg/stamped_scalar.hpp"
16#include "sensor_msgs/msg/joint_state.hpp"
17#include "std_srvs/srv/trigger.hpp"
18#include "tf2_ros/buffer.h"
19#include "tf2_ros/transform_listener.h"
void pose_callback(const nav_msgs::msg::Odometry &msg)
rclcpp::Publisher< fs_msgs::msg::FinishedSignal >::SharedPtr fsds_ebs_publisher_
void mission_state_callback(const fs_msgs::msg::GoSignal &msg) const
void finish() override
Function that sends the finish signal to the respective node.
rclcpp::Subscription< fs_msgs::msg::GoSignal >::SharedPtr fsds_state_subscription_
rclcpp::Subscription< nav_msgs::msg::Odometry >::SharedPtr fsds_position_subscription_
Responsible for path planning and trajectory generation for the autonomous vehicle.