Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
fsds.hpp
Go to the documentation of this file.
1#pragma once
2
4
5class SENode;
6
7class FsdsAdapter : public Adapter {
8 rclcpp::Subscription<fs_msgs::msg::GoSignal>::SharedPtr fsds_state_subscription_;
9 rclcpp::Publisher<fs_msgs::msg::FinishedSignal>::SharedPtr fsds_ebs_publisher_;
10
11 rclcpp::Subscription<sensor_msgs::msg::Imu>::SharedPtr _fs_imu_subscription_;
12 rclcpp::Subscription<fs_msgs::msg::WheelStates>::SharedPtr _fs_wheel_speeds_subscription_;
13
14public:
15 explicit FsdsAdapter(std::shared_ptr<SENode> se_node);
16
17 void mission_state_callback(const fs_msgs::msg::GoSignal& msg) const;
18 void finish() final;
19
20 void wheel_speeds_subscription_callback(const fs_msgs::msg::WheelStates& msg) const;
21};
Class that handles the communication between the SpeedEstimation node and the other nodes in the syst...
Definition adapter.hpp:21
rclcpp::Subscription< fs_msgs::msg::WheelStates >::SharedPtr _fs_wheel_speeds_subscription_
Definition fsds.hpp:12
rclcpp::Subscription< sensor_msgs::msg::Imu >::SharedPtr _fs_imu_subscription_
Definition fsds.hpp:11
rclcpp::Publisher< fs_msgs::msg::FinishedSignal >::SharedPtr fsds_ebs_publisher_
Definition fsds.hpp:9
void wheel_speeds_subscription_callback(const fs_msgs::msg::WheelStates &msg) const
Definition fsds.cpp:36
void mission_state_callback(const fs_msgs::msg::GoSignal &msg) const
Definition fsds.cpp:22
void finish() final
Function that sends the finish signal to the respective node.
Definition fsds.cpp:29
rclcpp::Subscription< fs_msgs::msg::GoSignal >::SharedPtr fsds_state_subscription_
Definition fsds.hpp:8
friend class FsdsAdapter
Definition planning.hpp:87
Class representing the main speed_est node responsible for publishing the calculated vehicle state wi...
Definition se_node.hpp:33