3#include "eufs_msgs/msg/can_state.hpp"
4#include "eufs_msgs/msg/car_state.hpp"
5#include "eufs_msgs/msg/cone_array_with_covariance.hpp"
6#include "eufs_msgs/srv/set_can_state.hpp"
23 void map_callback(
const eufs_msgs::msg::ConeArrayWithCovariance& msg);
Adapter class to interface with the EUFS simulator.
rclcpp::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr eufs_map_publisher_
void set_mission_state(int mission, int state)
rclcpp::Client< eufs_msgs::srv::SetCanState >::SharedPtr eufs_ebs_client_
void finish() override
Function that sends the finish signal to the respective node.
rclcpp::Client< eufs_msgs::srv::SetCanState >::SharedPtr eufs_mission_state_client_
void map_callback(const eufs_msgs::msg::ConeArrayWithCovariance &msg)
void mission_state_callback(const eufs_msgs::msg::CanState &msg) const
rclcpp::Subscription< eufs_msgs::msg::CarState >::SharedPtr eufs_pose_subscription_
void pose_callback(const eufs_msgs::msg::CarState &msg)
rclcpp::Subscription< eufs_msgs::msg::ConeArrayWithCovariance >::SharedPtr eufs_map_subscription_
rclcpp::Subscription< eufs_msgs::msg::CanState >::SharedPtr eufs_state_subscription_
Responsible for path planning and trajectory generation for the autonomous vehicle.