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

Node for perception tasks, such as ground removal and cone detection. More...

#include <perception_node.hpp>

Inheritance diagram for Perception:
Inheritance graph
Collaboration diagram for Perception:
Collaboration graph

Public Member Functions

 Perception (const PerceptionParameters &params)
 Constructor for the Perception node.
 
void point_cloud_callback (const sensor_msgs::msg::PointCloud2::SharedPtr msg)
 Callback function for the PointCloud2 subscription.
 

Static Public Member Functions

static PerceptionParameters load_config ()
 Turns the parameters in the yaml file into PerceptionParameters class.
 

Private Member Functions

void publish_cones (std::vector< Cluster > *cones, double exec_time, rclcpp::Time start_time)
 Publishes information about clusters (cones) using a custom ROS2 message.
 
void velocities_callback (const custom_interfaces::msg::Velocities &msg)
 Callback function for the Velocities subscription.
 
void lidar_timer_callback ()
 Callback function for the LiDAR timer to check for emergency.
 

Private Attributes

std::string _vehicle_frame_id_
 String for the vehicle's frame id.
 
std::string _adapter_
 String for the current adapter being used.
 
int16_t _mission_type_
 integer value for the current mission type running.
 
bool _publish_fov_trimmed_cloud_
 Whether to publish the FOV trimmed point cloud.
 
bool _publish_ground_removed_cloud_
 Whether to publish the ground removed point cloud.
 
bool _publish_wall_removed_cloud_
 Whether to publish the wall removed point cloud.
 
std::shared_ptr< std::unordered_map< int16_t, std::shared_ptr< FovTrimming > > > _fov_trim_map_
 Shared pointer to the FovTrimming object.
 
std::shared_ptr< GroundGrid_ground_grid_
 Model for the ground grid.
 
std::shared_ptr< GroundRemoval_ground_removal_
 Shared pointer to the GroundRemoval object.
 
std::shared_ptr< WallRemoval_wall_removal_
 Shared pointer to the WallRemoval object.
 
std::shared_ptr< Clustering_clustering_
 Shared pointer to the Clustering object.
 
std::shared_ptr< ConeDifferentiation_cone_differentiator_
 Shared pointer to ConeDifferentiation object.
 
std::shared_ptr< ConeEvaluator_cone_evaluator_
 Shared pointer to ConeEvaluator object.
 
std::shared_ptr< Deskew_deskew_
 Shared pointer to Deskew object.
 
rclcpp::Subscription< custom_interfaces::msg::OperationalStatus >::SharedPtr _operational_status_subscription
 Master Log subscription to aquire mission type.
 
rclcpp::Subscription< sensor_msgs::msg::PointCloud2 >::SharedPtr _point_cloud_subscription
 PointCloud2 subscription.
 
rclcpp::Subscription< custom_interfaces::msg::Velocities >::SharedPtr _velocities_subscription_
 
rclcpp::Publisher< custom_interfaces::msg::PerceptionOutput >::SharedPtr _cones_publisher
 ConeArray + exec publisher.
 
rclcpp::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr _cone_marker_array_
 MarkerArray publisher.
 
rclcpp::Publisher< std_msgs::msg::Float64MultiArray >::SharedPtr _perception_execution_time_publisher_
 Perception execution time publisher.
 
rclcpp::Publisher< sensor_msgs::msg::PointCloud2 >::SharedPtr _fov_trimmed_publisher_
 Point cloud after fov trimming publisher.
 
rclcpp::Publisher< sensor_msgs::msg::PointCloud2 >::SharedPtr _ground_removed_publisher_
 Point cloud after ground removal publisher.
 
rclcpp::Publisher< sensor_msgs::msg::PointCloud2 >::SharedPtr _wall_removed_publisher_
 Point cloud after wall removal publisher.
 
common_lib::structures::Velocities _vehicle_velocity_
 
rclcpp::TimerBase::SharedPtr lidar_off_timer_
 Timer to check for lidar emergency.
 
rclcpp::Client< std_srvs::srv::Trigger >::SharedPtr emergency_client_
 
std::shared_ptr< std::vector< double > > _execution_times_
 Vector to store execution times.
 

Detailed Description

Node for perception tasks, such as ground removal and cone detection.

This class is a ROS 2 node that subscribes to a PointCloud2 topic, performs ground removal using the specified GroundRemoval algorithm, and publishes cone detection results on a custom topic.

Definition at line 78 of file perception_node.hpp.

Constructor & Destructor Documentation

◆ Perception()

Perception::Perception ( const PerceptionParameters params)
explicit

Constructor for the Perception node.

Parameters
paramsThe parameters for perception.

Definition at line 186 of file perception_node.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ lidar_timer_callback()

void Perception::lidar_timer_callback ( )
private

Callback function for the LiDAR timer to check for emergency.

Definition at line 366 of file perception_node.cpp.

Here is the caller graph for this function:

◆ load_config()

PerceptionParameters Perception::load_config ( )
static

Turns the parameters in the yaml file into PerceptionParameters class.

Returns
parameters configured following yaml file.

Definition at line 12 of file perception_node.cpp.

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

◆ point_cloud_callback()

void Perception::point_cloud_callback ( const sensor_msgs::msg::PointCloud2::SharedPtr  msg)

Callback function for the PointCloud2 subscription.

Parameters
msgThe received PointCloud2 message.

Definition at line 258 of file perception_node.cpp.

Here is the call graph for this function:

◆ publish_cones()

void Perception::publish_cones ( std::vector< Cluster > *  cones,
double  exec_time,
rclcpp::Time  start_time 
)
private

Publishes information about clusters (cones) using a custom ROS2 message.

This function takes a vector of Cluster objects, extracts relevant information such as centroid and color, and publishes this information using a custom ROS2 message type ConeArray.

Parameters
conesA reference to a vector of Cluster objects representing the clusters (cones) to be published.

Definition at line 334 of file perception_node.cpp.

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

◆ velocities_callback()

void Perception::velocities_callback ( const custom_interfaces::msg::Velocities &  msg)
private

Callback function for the Velocities subscription.

Parameters
msgThe received Velocities message.

Definition at line 361 of file perception_node.cpp.

Here is the caller graph for this function:

Member Data Documentation

◆ _adapter_

std::string Perception::_adapter_
private

String for the current adapter being used.

Definition at line 101 of file perception_node.hpp.

◆ _clustering_

std::shared_ptr<Clustering> Perception::_clustering_
private

Shared pointer to the Clustering object.

Definition at line 111 of file perception_node.hpp.

◆ _cone_differentiator_

std::shared_ptr<ConeDifferentiation> Perception::_cone_differentiator_
private

Shared pointer to ConeDifferentiation object.

Definition at line 113 of file perception_node.hpp.

◆ _cone_evaluator_

std::shared_ptr<ConeEvaluator> Perception::_cone_evaluator_
private

Shared pointer to ConeEvaluator object.

Definition at line 114 of file perception_node.hpp.

◆ _cone_marker_array_

rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr Perception::_cone_marker_array_
private

MarkerArray publisher.

Definition at line 124 of file perception_node.hpp.

◆ _cones_publisher

rclcpp::Publisher<custom_interfaces::msg::PerceptionOutput>::SharedPtr Perception::_cones_publisher
private

ConeArray + exec publisher.

Definition at line 122 of file perception_node.hpp.

◆ _deskew_

std::shared_ptr<Deskew> Perception::_deskew_
private

Shared pointer to Deskew object.

Definition at line 115 of file perception_node.hpp.

◆ _execution_times_

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

Vector to store execution times.

Definition at line 138 of file perception_node.hpp.

◆ _fov_trim_map_

std::shared_ptr<std::unordered_map<int16_t, std::shared_ptr<FovTrimming> > > Perception::_fov_trim_map_
private

Shared pointer to the FovTrimming object.

Definition at line 107 of file perception_node.hpp.

◆ _fov_trimmed_publisher_

rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr Perception::_fov_trimmed_publisher_
private

Point cloud after fov trimming publisher.

Definition at line 128 of file perception_node.hpp.

◆ _ground_grid_

std::shared_ptr<GroundGrid> Perception::_ground_grid_
private

Model for the ground grid.

Definition at line 108 of file perception_node.hpp.

◆ _ground_removal_

std::shared_ptr<GroundRemoval> Perception::_ground_removal_
private

Shared pointer to the GroundRemoval object.

Definition at line 109 of file perception_node.hpp.

◆ _ground_removed_publisher_

rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr Perception::_ground_removed_publisher_
private

Point cloud after ground removal publisher.

Definition at line 130 of file perception_node.hpp.

◆ _mission_type_

int16_t Perception::_mission_type_
private

integer value for the current mission type running.

Definition at line 102 of file perception_node.hpp.

◆ _operational_status_subscription

rclcpp::Subscription<custom_interfaces::msg::OperationalStatus>::SharedPtr Perception::_operational_status_subscription
private

Master Log subscription to aquire mission type.

Definition at line 117 of file perception_node.hpp.

◆ _perception_execution_time_publisher_

rclcpp::Publisher<std_msgs::msg::Float64MultiArray>::SharedPtr Perception::_perception_execution_time_publisher_
private

Perception execution time publisher.

Definition at line 126 of file perception_node.hpp.

◆ _point_cloud_subscription

rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr Perception::_point_cloud_subscription
private

PointCloud2 subscription.

Definition at line 119 of file perception_node.hpp.

◆ _publish_fov_trimmed_cloud_

bool Perception::_publish_fov_trimmed_cloud_
private

Whether to publish the FOV trimmed point cloud.

Definition at line 103 of file perception_node.hpp.

◆ _publish_ground_removed_cloud_

bool Perception::_publish_ground_removed_cloud_
private

Whether to publish the ground removed point cloud.

Definition at line 104 of file perception_node.hpp.

◆ _publish_wall_removed_cloud_

bool Perception::_publish_wall_removed_cloud_
private

Whether to publish the wall removed point cloud.

Definition at line 105 of file perception_node.hpp.

◆ _vehicle_frame_id_

std::string Perception::_vehicle_frame_id_
private

String for the vehicle's frame id.

Definition at line 100 of file perception_node.hpp.

◆ _vehicle_velocity_

common_lib::structures::Velocities Perception::_vehicle_velocity_
private

Definition at line 134 of file perception_node.hpp.

◆ _velocities_subscription_

rclcpp::Subscription<custom_interfaces::msg::Velocities>::SharedPtr Perception::_velocities_subscription_
private

Definition at line 120 of file perception_node.hpp.

◆ _wall_removal_

std::shared_ptr<WallRemoval> Perception::_wall_removal_
private

Shared pointer to the WallRemoval object.

Definition at line 110 of file perception_node.hpp.

◆ _wall_removed_publisher_

rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr Perception::_wall_removed_publisher_
private

Point cloud after wall removal publisher.

Definition at line 132 of file perception_node.hpp.

◆ emergency_client_

rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr Perception::emergency_client_
private

Definition at line 137 of file perception_node.hpp.

◆ lidar_off_timer_

rclcpp::TimerBase::SharedPtr Perception::lidar_off_timer_
private

Timer to check for lidar emergency.

Definition at line 136 of file perception_node.hpp.


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