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
4#include "eufs_msgs/msg/cone_array_with_covariance.hpp"
5
6class SENode;
7
8class EufsAdapter : public Adapter {
9 rclcpp::Subscription<eufs_msgs::msg::ConeArrayWithCovariance>::SharedPtr
11 rclcpp::Subscription<eufs_msgs::msg::WheelSpeedsStamped>::SharedPtr
13 rclcpp::Subscription<eufs_msgs::msg::CanState>::SharedPtr eufs_state_subscription_;
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(std::shared_ptr<SENode> se_node);
19
20 void mission_state_callback(const eufs_msgs::msg::CanState& msg) const;
21 void finish() final;
22
24 const eufs_msgs::msg::ConeArrayWithCovariance& msg) const;
25 void wheel_speeds_subscription_callback(const eufs_msgs::msg::WheelSpeedsStamped& msg) const;
26};
Class that handles the communication between the SpeedEstimation node and the other nodes in the syst...
Definition adapter.hpp:21
Adapter class to interface with the EUFS simulator.
Definition eufs.hpp:14
void wheel_speeds_subscription_callback(const eufs_msgs::msg::WheelSpeedsStamped &msg) const
Definition eufs.cpp:109
rclcpp::Client< eufs_msgs::srv::SetCanState >::SharedPtr eufs_ebs_client_
Definition eufs.hpp:15
rclcpp::Client< eufs_msgs::srv::SetCanState >::SharedPtr eufs_mission_state_client_
Definition eufs.hpp:14
void finish() final
Function that sends the finish signal to the respective node.
Definition eufs.cpp:47
void mission_state_callback(const eufs_msgs::msg::CanState &msg) const
Definition eufs.cpp:37
rclcpp::Subscription< eufs_msgs::msg::ConeArrayWithCovariance >::SharedPtr _perception_detections_subscription_
Subscriber for simulated perception detections.
Definition eufs.hpp:10
rclcpp::Subscription< eufs_msgs::msg::WheelSpeedsStamped >::SharedPtr _eufs_wheel_speeds_subscription_
Subscriber for wheel speeds and steering angle.
Definition eufs.hpp:12
void perception_detections_subscription_callback(const eufs_msgs::msg::ConeArrayWithCovariance &msg) const
Definition eufs.cpp:51
rclcpp::Subscription< eufs_msgs::msg::CanState >::SharedPtr eufs_state_subscription_
Definition eufs.hpp:13
friend class EufsAdapter
Definition planning.hpp:86
Class representing the main speed_est node responsible for publishing the calculated vehicle state wi...
Definition se_node.hpp:33