|
Formula Student Autonomous Systems
The code for the main driverless system
|
Class responsible for the ROS2 communication of the control module. More...
#include <ros_node.hpp>


Public Member Functions | |
| ControlNode (const ControlParameters ¶ms) | |
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< ControlSolver > | control_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_ |
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.
|
explicit |
|
private |
Function that publishes control commands on timer ticks.
Definition at line 30 of file ros_node.cpp.

|
protected |
Called when a new path is received.
| msg | The received path message |
Definition at line 51 of file ros_node.cpp.
|
privatepure virtual |
Adapters override this function to publish control commands in their environment.
| cmd | Control command to be published |
Implemented in EufsAdapter, PacSimAdapter, and VehicleAdapter.

|
protected |
Called when a new vehicle pose is received.
| msg | The received pose message |
Definition at line 47 of file ros_node.cpp.

|
protected |
Called when a new velocity is received.
| msg | The received velocity message |
Definition at line 55 of file ros_node.cpp.

|
private |
Definition at line 51 of file ros_node.hpp.
|
private |
Definition at line 57 of file ros_node.hpp.
|
private |
Definition at line 63 of file ros_node.hpp.
|
private |
Definition at line 60 of file ros_node.hpp.
|
protected |
Definition at line 28 of file ros_node.hpp.
|
protected |
Definition at line 29 of file ros_node.hpp.
|
private |
Definition at line 66 of file ros_node.hpp.
|
private |
Definition at line 54 of file ros_node.hpp.
|
private |
Definition at line 67 of file ros_node.hpp.
|
private |
Definition at line 68 of file ros_node.hpp.