4#include "custom_interfaces/msg/path_point_array.hpp"
5#include "custom_interfaces/msg/velocities.hpp"
6#include "custom_interfaces/msg/pose.hpp"
15 std::shared_ptr<ControlParameters>
params_;
20 virtual void path_callback(
const custom_interfaces::msg::PathPointArray& msg) = 0;
43 virtual void publish_solver_data(std::shared_ptr<rclcpp::Node> node, std::map<std::string, std::shared_ptr<rclcpp::PublisherBase>>& publisher_map) = 0;
Base (abstract) class for longitudinal controllers (the ones that calculate throttle)
virtual ~LongitudinalController()=default
virtual void vehicle_state_callback(const custom_interfaces::msg::Velocities &msg)=0
Called when the car state (currently just velocity) is updated.
virtual void path_callback(const custom_interfaces::msg::PathPointArray &msg)=0
Called when a new path is sent by Path Planning.
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.
virtual void vehicle_pose_callback(const custom_interfaces::msg::Pose &msg)=0
Called when the car pose is updated by SLAM.
virtual common_lib::structures::ControlCommand get_throttle_command()=0
Returns the throttle command calculated by the solver (only throttle)
LongitudinalController(const ControlParameters ¶ms)
std::shared_ptr< ControlParameters > params_