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 "ackermann_msgs/msg/ackermann_drive_stamped.hpp"
4#include "eufs_msgs/msg/car_state.hpp"
6
14class EufsAdapter : public ControlNode {
15private:
16 rclcpp::Publisher<ackermann_msgs::msg::AckermannDriveStamped>::SharedPtr control_pub_;
17 rclcpp::Subscription<eufs_msgs::msg::CarState>::SharedPtr vehicle_pose_sub_;
18
19public:
20 explicit EufsAdapter(const ControlParameters& params);
24 void vehicle_state_callback(const eufs_msgs::msg::CarState& msg);
26};
Class responsible for the ROS2 communication of the control module.
Definition ros_node.hpp:26
Adapter class to interface with the EUFS simulator.
Definition eufs.hpp:14
rclcpp::Subscription< eufs_msgs::msg::CarState >::SharedPtr vehicle_pose_sub_
Definition eufs.hpp:17
void publish_command(common_lib::structures::ControlCommand cmd) override
Adapters override this function to publish control commands in their environment.
Definition eufs.cpp:34
rclcpp::Publisher< ackermann_msgs::msg::AckermannDriveStamped >::SharedPtr control_pub_
Definition eufs.hpp:16
void vehicle_state_callback(const eufs_msgs::msg::CarState &msg)
Callback function for velocities and poses, which are coupled in EUFS.
Definition eufs.cpp:19
friend class EufsAdapter
Definition planning.hpp:86