Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
ControlNode Class Referenceabstract

Class responsible for the ROS2 communication of the control module. More...

#include <ros_node.hpp>

Inheritance diagram for ControlNode:
Inheritance graph
Collaboration diagram for ControlNode:
Collaboration graph

Public Member Functions

 ControlNode (const ControlParameters &params)
 

Protected Member Functions

void vehicle_pose_callback (const custom_interfaces::msg::Pose &msg)
 Called when a new vehicle pose is received.
 
void path_callback (const custom_interfaces::msg::PathPointArray &msg)
 Called when a new path is received.
 
void vehicle_state_callback (const custom_interfaces::msg::Velocities &msg)
 Called when a new velocity is received.
 

Protected Attributes

bool go_signal_ {false}
 
ControlParameters params_
 

Private Member Functions

void control_timer_callback ()
 Function that publishes control commands on timer ticks.
 
virtual void publish_command (common_lib::structures::ControlCommand cmd)=0
 Adapters override this function to publish control commands in their environment.
 

Private Attributes

std::shared_ptr< std::vector< double > > _execution_times_
 
std::map< std::string, std::shared_ptr< rclcpp::PublisherBase > > publisher_map_
 
std::shared_ptr< ControlSolvercontrol_solver_
 
rclcpp::Publisher< std_msgs::msg::Float64MultiArray >::SharedPtr execution_time_pub_
 
rclcpp::TimerBase::SharedPtr control_timer_
 
rclcpp::Subscription< custom_interfaces::msg::PathPointArray >::SharedPtr path_point_array_sub_
 
rclcpp::Subscription< custom_interfaces::msg::Pose >::SharedPtr vehicle_pose_sub_
 
rclcpp::Subscription< custom_interfaces::msg::Velocities >::SharedPtr velocity_sub_
 

Detailed Description

Class responsible for the ROS2 communication of the control module.

This class inherits from rclcpp::Node, subscribing to current state (velocity), pose and path topics, and publishing a control command.

Definition at line 26 of file ros_node.hpp.

Constructor & Destructor Documentation

◆ ControlNode()

ControlNode::ControlNode ( const ControlParameters params)
explicit

Definition at line 5 of file ros_node.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ control_timer_callback()

void ControlNode::control_timer_callback ( )
private

Function that publishes control commands on timer ticks.

Definition at line 30 of file ros_node.cpp.

Here is the call graph for this function:

◆ path_callback()

void ControlNode::path_callback ( const custom_interfaces::msg::PathPointArray &  msg)
protected

Called when a new path is received.

Parameters
msgThe received path message

Definition at line 51 of file ros_node.cpp.

◆ publish_command()

virtual void ControlNode::publish_command ( common_lib::structures::ControlCommand  cmd)
privatepure virtual

Adapters override this function to publish control commands in their environment.

Parameters
cmdControl command to be published

Implemented in EufsAdapter, PacSimAdapter, and VehicleAdapter.

Here is the caller graph for this function:

◆ vehicle_pose_callback()

void ControlNode::vehicle_pose_callback ( const custom_interfaces::msg::Pose &  msg)
protected

Called when a new vehicle pose is received.

Parameters
msgThe received pose message

Definition at line 47 of file ros_node.cpp.

Here is the caller graph for this function:

◆ vehicle_state_callback()

void ControlNode::vehicle_state_callback ( const custom_interfaces::msg::Velocities &  msg)
protected

Called when a new velocity is received.

Parameters
msgThe received velocity message

Definition at line 55 of file ros_node.cpp.

Here is the caller graph for this function:

Member Data Documentation

◆ _execution_times_

std::shared_ptr<std::vector<double> > ControlNode::_execution_times_
private

Definition at line 51 of file ros_node.hpp.

◆ control_solver_

std::shared_ptr<ControlSolver> ControlNode::control_solver_
private

Definition at line 57 of file ros_node.hpp.

◆ control_timer_

rclcpp::TimerBase::SharedPtr ControlNode::control_timer_
private

Definition at line 63 of file ros_node.hpp.

◆ execution_time_pub_

rclcpp::Publisher<std_msgs::msg::Float64MultiArray>::SharedPtr ControlNode::execution_time_pub_
private

Definition at line 60 of file ros_node.hpp.

◆ go_signal_

bool ControlNode::go_signal_ {false}
protected

Definition at line 28 of file ros_node.hpp.

◆ params_

ControlParameters ControlNode::params_
protected

Definition at line 29 of file ros_node.hpp.

◆ path_point_array_sub_

rclcpp::Subscription<custom_interfaces::msg::PathPointArray>::SharedPtr ControlNode::path_point_array_sub_
private

Definition at line 66 of file ros_node.hpp.

◆ publisher_map_

std::map<std::string, std::shared_ptr<rclcpp::PublisherBase> > ControlNode::publisher_map_
private

Definition at line 54 of file ros_node.hpp.

◆ vehicle_pose_sub_

rclcpp::Subscription<custom_interfaces::msg::Pose>::SharedPtr ControlNode::vehicle_pose_sub_
private

Definition at line 67 of file ros_node.hpp.

◆ velocity_sub_

rclcpp::Subscription<custom_interfaces::msg::Velocities>::SharedPtr ControlNode::velocity_sub_
private

Definition at line 68 of file ros_node.hpp.


The documentation for this class was generated from the following files: