Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
base_decoupled_controller.cpp
Go to the documentation of this file.
2
4 lateral_controller_(lateral_controller_map.at(params.lateral_controller_)(params)),
5 longitudinal_controller_(longitudinal_controller_map.at(params.longitudinal_controller_)(params)) {}
6
7void DecoupledController::path_callback(const custom_interfaces::msg::PathPointArray& msg) {
9 longitudinal_controller_->path_callback(msg);
10}
11
12void DecoupledController::vehicle_state_callback(const custom_interfaces::msg::Velocities& msg) {
13 lateral_controller_->vehicle_state_callback(msg);
14 longitudinal_controller_->vehicle_state_callback(msg);
15}
16
17void DecoupledController::vehicle_pose_callback(const custom_interfaces::msg::Pose& msg) {
18 lateral_controller_->vehicle_pose_callback(msg);
19 longitudinal_controller_->vehicle_pose_callback(msg);
20}
21
23 common_lib::structures::ControlCommand command = this->longitudinal_controller_->get_throttle_command();
24 command.steering_angle = this->lateral_controller_->get_steering_command();
25 return command;
26}
27
28void DecoupledController::publish_solver_data(std::shared_ptr<rclcpp::Node> node, std::map<std::string, std::shared_ptr<rclcpp::PublisherBase>>& publisher_map) {
29 lateral_controller_->publish_solver_data(node, publisher_map);
30 longitudinal_controller_->publish_solver_data(node, publisher_map);
31}
Base class for control solvers, that calculate both lateral and longitudinal control commands.
virtual void path_callback(const custom_interfaces::msg::PathPointArray &msg)=0
Called when a new path is sent by Path Planning.
std::shared_ptr< LongitudinalController > longitudinal_controller_
void path_callback(const custom_interfaces::msg::PathPointArray &msg) override
Called when a new path is sent by Path Planning.
std::shared_ptr< LateralController > lateral_controller_
void publish_solver_data(std::shared_ptr< rclcpp::Node > node, std::map< std::string, std::shared_ptr< rclcpp::PublisherBase > > &publisher_map) override
Publishes solver specific data using the provided ControlNode.
common_lib::structures::ControlCommand get_control_command() override
Returns the control command calculated by the solver.
DecoupledController(const ControlParameters &params)
void vehicle_state_callback(const custom_interfaces::msg::Velocities &msg) override
Called when the car state (currently just velocity) is updated.
void vehicle_pose_callback(const custom_interfaces::msg::Pose &msg) override
Called when the car pose is updated by SLAM.
const std::map< std::string, std::function< std::shared_ptr< LateralController >(const ControlParameters &)>, std::less<> > lateral_controller_map
Definition map.hpp:15
const std::map< std::string, std::function< std::shared_ptr< LongitudinalController >(const ControlParameters &)>, std::less<> > longitudinal_controller_map
Definition map.hpp:15