|
Formula Student Autonomous Systems
The code for the main driverless system
|
Node for perception tasks, such as ground removal and cone detection. More...
#include <perception_node.hpp>


Public Member Functions | |
| Perception (const PerceptionParameters ¶ms) | |
| 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. | |
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.
|
explicit |
Constructor for the Perception node.
| params | The parameters for perception. |
Definition at line 186 of file perception_node.cpp.

|
private |
Callback function for the LiDAR timer to check for emergency.
Definition at line 366 of file perception_node.cpp.

|
static |
Turns the parameters in the yaml file into PerceptionParameters class.
Definition at line 12 of file perception_node.cpp.


| void Perception::point_cloud_callback | ( | const sensor_msgs::msg::PointCloud2::SharedPtr | msg | ) |
Callback function for the PointCloud2 subscription.
| msg | The received PointCloud2 message. |
Definition at line 258 of file perception_node.cpp.

|
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.
| cones | A reference to a vector of Cluster objects representing the clusters (cones) to be published. |
Definition at line 334 of file perception_node.cpp.


|
private |
Callback function for the Velocities subscription.
| msg | The received Velocities message. |
Definition at line 361 of file perception_node.cpp.

|
private |
String for the current adapter being used.
Definition at line 101 of file perception_node.hpp.
|
private |
Shared pointer to the Clustering object.
Definition at line 111 of file perception_node.hpp.
|
private |
Shared pointer to ConeDifferentiation object.
Definition at line 113 of file perception_node.hpp.
|
private |
Shared pointer to ConeEvaluator object.
Definition at line 114 of file perception_node.hpp.
|
private |
MarkerArray publisher.
Definition at line 124 of file perception_node.hpp.
|
private |
ConeArray + exec publisher.
Definition at line 122 of file perception_node.hpp.
|
private |
Shared pointer to Deskew object.
Definition at line 115 of file perception_node.hpp.
|
private |
Vector to store execution times.
Definition at line 138 of file perception_node.hpp.
|
private |
Shared pointer to the FovTrimming object.
Definition at line 107 of file perception_node.hpp.
|
private |
Point cloud after fov trimming publisher.
Definition at line 128 of file perception_node.hpp.
|
private |
Model for the ground grid.
Definition at line 108 of file perception_node.hpp.
|
private |
Shared pointer to the GroundRemoval object.
Definition at line 109 of file perception_node.hpp.
|
private |
Point cloud after ground removal publisher.
Definition at line 130 of file perception_node.hpp.
|
private |
integer value for the current mission type running.
Definition at line 102 of file perception_node.hpp.
|
private |
Master Log subscription to aquire mission type.
Definition at line 117 of file perception_node.hpp.
|
private |
Perception execution time publisher.
Definition at line 126 of file perception_node.hpp.
|
private |
PointCloud2 subscription.
Definition at line 119 of file perception_node.hpp.
|
private |
Whether to publish the FOV trimmed point cloud.
Definition at line 103 of file perception_node.hpp.
|
private |
Whether to publish the ground removed point cloud.
Definition at line 104 of file perception_node.hpp.
|
private |
Whether to publish the wall removed point cloud.
Definition at line 105 of file perception_node.hpp.
|
private |
String for the vehicle's frame id.
Definition at line 100 of file perception_node.hpp.
|
private |
Definition at line 134 of file perception_node.hpp.
|
private |
Definition at line 120 of file perception_node.hpp.
|
private |
Shared pointer to the WallRemoval object.
Definition at line 110 of file perception_node.hpp.
|
private |
Point cloud after wall removal publisher.
Definition at line 132 of file perception_node.hpp.
|
private |
Definition at line 137 of file perception_node.hpp.
|
private |
Timer to check for lidar emergency.
Definition at line 136 of file perception_node.hpp.