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

Class representing the main speed_est node responsible for publishing the calculated vehicle state with speed and the map. More...

#include <se_node.hpp>

Inheritance diagram for SENode:
Inheritance graph
Collaboration diagram for SENode:
Collaboration graph

Public Member Functions

 SENode ()
 Constructor of the main node, most things are received by launch parameter.
 

Private Member Functions

void _perception_subscription_callback (const custom_interfaces::msg::ConeArray &msg)
 Callback that updates everytime information is received from the perception module.
 
void _imu_subscription_callback (const sensor_msgs::msg::Imu &imu_msg)
 Function to be called everytime information is received from the IMU.
 
void _wheel_speeds_subscription_callback (double rl_speed, double rr_speed, double fl_speed, double fr_speed, double steering_angle, const rclcpp::Time &timestamp)
 Function to be called everytime information is received from the wheel encoders.
 
void _update_and_publish ()
 Executes:
 
void _publish_vehicle_state ()
 publishes the localization ('vehicle_localization') to the topic vehicle_location
 
void _publish_vehicle_state_wss ()
 publishes the localization ('vehicle_localization') to the topic vehicle_location
 
void _publish_vehicle_state_imu ()
 publishes the localization ('vehicle_localization') to the topic vehicle_location
 
void _publish_map ()
 publishes the map ('track_map') to the topic track_map
 
void _ekf_step ()
 executes the prediction step of the EKF
 

Private Attributes

rclcpp::Subscription< custom_interfaces::msg::ConeArray >::SharedPtr _perception_subscription_
 
rclcpp::Publisher< custom_interfaces::msg::VehicleState >::SharedPtr _vehicle_state_publisher_
 
rclcpp::Publisher< custom_interfaces::msg::VehicleState >::SharedPtr _vehicle_state_publisher_wss_
 
rclcpp::Publisher< custom_interfaces::msg::VehicleState >::SharedPtr _vehicle_state_publisher_imu_
 
rclcpp::Publisher< custom_interfaces::msg::ConeArray >::SharedPtr _map_publisher_
 
rclcpp::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr _visualization_map_publisher_
 
rclcpp::Publisher< std_msgs::msg::Float64 >::SharedPtr _correction_execution_time_publisher_
 
rclcpp::Publisher< std_msgs::msg::Float64 >::SharedPtr _prediction_execution_time_publisher_
 
rclcpp::TimerBase::SharedPtr _timer_
 timer
 
std::shared_ptr< ExtendedKalmanFilter_ekf_
 SLAM EKF object.
 
std::shared_ptr< std::vector< common_lib::structures::Cone > > _perception_map_
 
std::shared_ptr< MotionUpdate_motion_update_
 
std::shared_ptr< std::vector< common_lib::structures::Cone > > _track_map_
 
std::shared_ptr< common_lib::structures::VehicleState_vehicle_state_
 
common_lib::competition_logic::Mission _mission_
 
rclcpp::Publisher< visualization_msgs::msg::Marker >::SharedPtr _position_publisher_
 
rclcpp::Publisher< visualization_msgs::msg::Marker >::SharedPtr _car_model_publisher_
 
bool _go_
 
bool _use_odometry_
 flag to start the mission
 
bool _use_simulated_perception_
 
std::string _adapter_name_
 
std::shared_ptr< Adapter_adapter_
 
std::mutex _mutex_
 
std::shared_ptr< common_lib::car_parameters::CarParameters_car_parameters_ = std::make_shared<common_lib::car_parameters::CarParameters>()
 Mutex used to lock EKF access.
 

Friends

class Adapter
 
class EufsAdapter
 
class FsdsAdapter
 
class PacsimAdapter
 
class VehicleAdapter
 

Detailed Description

Class representing the main speed_est node responsible for publishing the calculated vehicle state with speed and the map.

As well as, subscribing and interpreting information, such as the cone's position and colors, from the perception module.

Definition at line 33 of file se_node.hpp.

Constructor & Destructor Documentation

◆ SENode()

SENode::SENode ( )

Constructor of the main node, most things are received by launch parameter.

Definition at line 24 of file se_node.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ _ekf_step()

void SENode::_ekf_step ( )
private

executes the prediction step of the EKF

Definition at line 403 of file se_node.cpp.

Here is the caller graph for this function:

◆ _imu_subscription_callback()

void SENode::_imu_subscription_callback ( const sensor_msgs::msg::Imu &  imu_msg)
private

Function to be called everytime information is received from the IMU.

Parameters
rotational_velocity
acceleration_x
acceleration_y

Definition at line 141 of file se_node.cpp.

Here is the call graph for this function:

◆ _perception_subscription_callback()

void SENode::_perception_subscription_callback ( const custom_interfaces::msg::ConeArray &  msg)
private

Callback that updates everytime information is received from the perception module.

Parameters
msgMessage containing the array of perceived cones

Definition at line 103 of file se_node.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _publish_map()

void SENode::_publish_map ( )
private

publishes the map ('track_map') to the topic track_map

Definition at line 378 of file se_node.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _publish_vehicle_state()

void SENode::_publish_vehicle_state ( )
private

publishes the localization ('vehicle_localization') to the topic vehicle_location

Definition at line 252 of file se_node.cpp.

Here is the caller graph for this function:

◆ _publish_vehicle_state_imu()

void SENode::_publish_vehicle_state_imu ( )
private

publishes the localization ('vehicle_localization') to the topic vehicle_location

Definition at line 357 of file se_node.cpp.

Here is the caller graph for this function:

◆ _publish_vehicle_state_wss()

void SENode::_publish_vehicle_state_wss ( )
private

publishes the localization ('vehicle_localization') to the topic vehicle_location

Definition at line 277 of file se_node.cpp.

Here is the caller graph for this function:

◆ _update_and_publish()

void SENode::_update_and_publish ( )
private

Executes:

  • the prediction, validation and discovery steps of the EKF
  • publication of localization
  • publication of map

Definition at line 415 of file se_node.cpp.

Here is the call graph for this function:

◆ _wheel_speeds_subscription_callback()

void SENode::_wheel_speeds_subscription_callback ( double  rl_speed,
double  rr_speed,
double  fl_speed,
double  fr_speed,
double  steering_angle,
const rclcpp::Time &  timestamp 
)
private

Function to be called everytime information is received from the wheel encoders.

Parameters
lb_speedwheel speeds in rpm
lf_speedwheel speeds in rpm
rb_speedwheel speeds in rpm
rf_speedwheel speeds in rpm
steering_anglesteering angle in radians
timestamptimestamp of the message

Definition at line 191 of file se_node.cpp.

Here is the call graph for this function:

Friends And Related Symbol Documentation

◆ Adapter

friend class Adapter
friend

Definition at line 140 of file se_node.hpp.

◆ EufsAdapter

friend class EufsAdapter
friend

Definition at line 141 of file se_node.hpp.

◆ FsdsAdapter

friend class FsdsAdapter
friend

Definition at line 142 of file se_node.hpp.

◆ PacsimAdapter

friend class PacsimAdapter
friend

Definition at line 143 of file se_node.hpp.

◆ VehicleAdapter

friend class VehicleAdapter
friend

Definition at line 144 of file se_node.hpp.

Member Data Documentation

◆ _adapter_

std::shared_ptr<Adapter> SENode::_adapter_
private

Definition at line 55 of file se_node.hpp.

◆ _adapter_name_

std::string SENode::_adapter_name_
private

Definition at line 54 of file se_node.hpp.

◆ _car_model_publisher_

rclcpp::Publisher<visualization_msgs::msg::Marker>::SharedPtr SENode::_car_model_publisher_
private

Definition at line 50 of file se_node.hpp.

◆ _car_parameters_

std::shared_ptr<common_lib::car_parameters::CarParameters> SENode::_car_parameters_ = std::make_shared<common_lib::car_parameters::CarParameters>()
private

Mutex used to lock EKF access.

Definition at line 57 of file se_node.hpp.

◆ _correction_execution_time_publisher_

rclcpp::Publisher<std_msgs::msg::Float64>::SharedPtr SENode::_correction_execution_time_publisher_
private

Definition at line 40 of file se_node.hpp.

◆ _ekf_

std::shared_ptr<ExtendedKalmanFilter> SENode::_ekf_
private

SLAM EKF object.

Definition at line 43 of file se_node.hpp.

◆ _go_

bool SENode::_go_
private

Definition at line 51 of file se_node.hpp.

◆ _map_publisher_

rclcpp::Publisher<custom_interfaces::msg::ConeArray>::SharedPtr SENode::_map_publisher_
private

Definition at line 38 of file se_node.hpp.

◆ _mission_

common_lib::competition_logic::Mission SENode::_mission_
private

Definition at line 48 of file se_node.hpp.

◆ _motion_update_

std::shared_ptr<MotionUpdate> SENode::_motion_update_
private

Definition at line 45 of file se_node.hpp.

◆ _mutex_

std::mutex SENode::_mutex_
private

Definition at line 56 of file se_node.hpp.

◆ _perception_map_

std::shared_ptr<std::vector<common_lib::structures::Cone> > SENode::_perception_map_
private

Definition at line 44 of file se_node.hpp.

◆ _perception_subscription_

rclcpp::Subscription<custom_interfaces::msg::ConeArray>::SharedPtr SENode::_perception_subscription_
private

Definition at line 34 of file se_node.hpp.

◆ _position_publisher_

rclcpp::Publisher<visualization_msgs::msg::Marker>::SharedPtr SENode::_position_publisher_
private

Definition at line 49 of file se_node.hpp.

◆ _prediction_execution_time_publisher_

rclcpp::Publisher<std_msgs::msg::Float64>::SharedPtr SENode::_prediction_execution_time_publisher_
private

Definition at line 41 of file se_node.hpp.

◆ _timer_

rclcpp::TimerBase::SharedPtr SENode::_timer_
private

timer

Definition at line 42 of file se_node.hpp.

◆ _track_map_

std::shared_ptr<std::vector<common_lib::structures::Cone> > SENode::_track_map_
private

Definition at line 46 of file se_node.hpp.

◆ _use_odometry_

bool SENode::_use_odometry_
private

flag to start the mission

Definition at line 52 of file se_node.hpp.

◆ _use_simulated_perception_

bool SENode::_use_simulated_perception_
private

Definition at line 53 of file se_node.hpp.

◆ _vehicle_state_

std::shared_ptr<common_lib::structures::VehicleState> SENode::_vehicle_state_
private

Definition at line 47 of file se_node.hpp.

◆ _vehicle_state_publisher_

rclcpp::Publisher<custom_interfaces::msg::VehicleState>::SharedPtr SENode::_vehicle_state_publisher_
private

Definition at line 35 of file se_node.hpp.

◆ _vehicle_state_publisher_imu_

rclcpp::Publisher<custom_interfaces::msg::VehicleState>::SharedPtr SENode::_vehicle_state_publisher_imu_
private

Definition at line 37 of file se_node.hpp.

◆ _vehicle_state_publisher_wss_

rclcpp::Publisher<custom_interfaces::msg::VehicleState>::SharedPtr SENode::_vehicle_state_publisher_wss_
private

Definition at line 36 of file se_node.hpp.

◆ _visualization_map_publisher_

rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr SENode::_visualization_map_publisher_
private

Definition at line 39 of file se_node.hpp.


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