3#include "custom_interfaces/msg/path_point_array.hpp"
4#include "custom_interfaces/msg/velocities.hpp"
5#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 class for control solvers, that calculate both lateral and longitudinal control commands.
ControlSolver(const ControlParameters ¶ms)
virtual void vehicle_state_callback(const custom_interfaces::msg::Velocities &msg)=0
Called when the car state (currently just velocity) is updated.
virtual ~ControlSolver()=default
virtual void path_callback(const custom_interfaces::msg::PathPointArray &msg)=0
Called when a new path is sent by Path Planning.
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.
std::shared_ptr< ControlParameters > params_
virtual common_lib::structures::ControlCommand get_control_command()=0
Returns the control command calculated by the solver.