Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
eufs.hpp
Go to the documentation of this file.
1#pragma once
2
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"
8
9class EufsAdapter : public Planning {
10 rclcpp::Subscription<eufs_msgs::msg::CanState>::SharedPtr eufs_state_subscription_;
11 rclcpp::Subscription<eufs_msgs::msg::CarState>::SharedPtr eufs_pose_subscription_;
12 rclcpp::Subscription<eufs_msgs::msg::ConeArrayWithCovariance>::SharedPtr eufs_map_subscription_;
13 rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr eufs_map_publisher_;
14 rclcpp::Client<eufs_msgs::srv::SetCanState>::SharedPtr eufs_mission_state_client_;
15 rclcpp::Client<eufs_msgs::srv::SetCanState>::SharedPtr eufs_ebs_client_;
16
17public:
18 explicit EufsAdapter(const PlanningParameters& params);
19
20 void mission_state_callback(eufs_msgs::msg::CanState msg);
21 void set_mission_state(int mission, int state);
22 void pose_callback(const eufs_msgs::msg::CarState& msg);
23 void map_callback(const eufs_msgs::msg::ConeArrayWithCovariance& msg);
24 void finish() override;
25};
Adapter class to interface with the EUFS simulator.
Definition eufs.hpp:14
rclcpp::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr eufs_map_publisher_
Definition eufs.hpp:13
void set_mission_state(int mission, int state)
Definition eufs.cpp:114
rclcpp::Client< eufs_msgs::srv::SetCanState >::SharedPtr eufs_ebs_client_
Definition eufs.hpp:15
void finish() override
Function that sends the finish signal to the respective node.
rclcpp::Client< eufs_msgs::srv::SetCanState >::SharedPtr eufs_mission_state_client_
Definition eufs.hpp:14
void map_callback(const eufs_msgs::msg::ConeArrayWithCovariance &msg)
Definition eufs.cpp:143
void mission_state_callback(const eufs_msgs::msg::CanState &msg) const
Definition eufs.cpp:37
rclcpp::Subscription< eufs_msgs::msg::CarState >::SharedPtr eufs_pose_subscription_
Definition eufs.hpp:11
void pose_callback(const eufs_msgs::msg::CarState &msg)
Definition eufs.cpp:126
rclcpp::Subscription< eufs_msgs::msg::ConeArrayWithCovariance >::SharedPtr eufs_map_subscription_
Definition eufs.hpp:12
rclcpp::Subscription< eufs_msgs::msg::CanState >::SharedPtr eufs_state_subscription_
Definition eufs.hpp:13
Responsible for path planning and trajectory generation for the autonomous vehicle.
Definition planning.hpp:54
friend class EufsAdapter
Definition planning.hpp:86