Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
base_lateral_controller.hpp
Go to the documentation of this file.
1#pragma once
2
3#include "custom_interfaces/msg/path_point_array.hpp"
4#include "custom_interfaces/msg/velocities.hpp"
5#include "custom_interfaces/msg/pose.hpp"
8
14protected:
15 std::shared_ptr<ControlParameters> params_;
16public:
20 virtual void path_callback(const custom_interfaces::msg::PathPointArray& msg) = 0;
21
25 virtual void vehicle_state_callback(const custom_interfaces::msg::Velocities& msg) = 0;
26
30 virtual void vehicle_pose_callback(const custom_interfaces::msg::Pose& msg) = 0;
31
35 virtual double get_steering_command() = 0;
36
43 virtual void publish_solver_data(std::shared_ptr<rclcpp::Node> node, std::map<std::string, std::shared_ptr<rclcpp::PublisherBase>>& publisher_map) = 0;
44
45 LateralController(const ControlParameters& params) : params_(std::make_shared<ControlParameters>(params)) {};
46 virtual ~LateralController() = default;
47};
Base (abstract) class for lateral control solvers (that calculate steering command)
virtual double get_steering_command()=0
Returns the steering command calculated by the solver.
virtual ~LateralController()=default
virtual void path_callback(const custom_interfaces::msg::PathPointArray &msg)=0
Called when a new path is sent by Path Planning.
std::shared_ptr< ControlParameters > params_
virtual void vehicle_state_callback(const custom_interfaces::msg::Velocities &msg)=0
Called when the car state (currently just velocity) is updated.
virtual void vehicle_pose_callback(const custom_interfaces::msg::Pose &msg)=0
Called when the car pose is updated by SLAM.
virtual void publish_solver_data(std::shared_ptr< rclcpp::Node > node, std::map< std::string, std::shared_ptr< rclcpp::PublisherBase > > &publisher_map)=0
Publishes solver specific data using the provided ControlNode.
LateralController(const ControlParameters &params)
Hash function for cones.
Definition cone.hpp:36