|
Formula Student Autonomous Systems
The code for the main driverless system
|
Represents a cluster of 3D points using PCL (Point Cloud Library). More...
#include <cluster.hpp>

Public Member Functions | |
| Cluster (const sensor_msgs::msg::PointCloud2::SharedPtr &point_cloud, const std::vector< int > &point_indices) | |
| Constructor for the Cluster class. | |
| Eigen::Vector4f | get_centroid () |
| Get the centroid of the cluster. | |
| Eigen::Vector4f | get_center (Plane &plane) |
| Get the Center of the cone's cluster. | |
| std::string | get_color () |
| Get the color associated with the cluster. | |
| void | set_color (const std::string &new_color) |
| Set the color for the cluster. | |
| void | set_point_indices (const std::vector< int > &new_point_indices) |
| Set the Point Cloud data for the cluster. | |
| const std::vector< int > & | get_point_indices () |
| Get the Point Cloud data of the cluster. | |
| const sensor_msgs::msg::PointCloud2::SharedPtr & | get_point_cloud () |
| Get the Point Cloud data of the cluster. | |
| void | set_confidence (double newConfidence) |
| Set the Confidence of the cluster to be or not to be a cone. | |
| double | get_confidence () |
| Get the Confidence of the cluster to be (or not to be) a cone. | |
| void | set_z_score (double mean_x, double std_dev_x, double mean_y, double std_dev_y) |
| Set the z score object on the x and y axis. | |
| double | get_z_score_x () const |
| Get the z score on x-axis of an object. | |
| double | get_z_score_y () const |
| Get the z score on y-axis of an object. | |
| bool | get_is_large () |
| Get cluster's corresponding cone size. | |
| void | set_is_large () |
| Set cluster as a contender for a large cone. | |
Static Public Member Functions | |
| static std::tuple< double, double, double, double > | calculate_mean_and_std_dev (std::vector< Cluster > &clusters) |
| Calculates the mean and standard deviation on x and y axis. | |
| static void | set_z_scores (std::vector< Cluster > &clusters) |
| Set the z scores object on every cluster of the vector. | |
Private Attributes | |
| const sensor_msgs::msg::PointCloud2::SharedPtr | _point_cloud_ |
| Point cloud data for the cluster. | |
| std::vector< int > | _point_indices_ |
| Indices of points in the cluster. | |
| std::string | _color_ = "undefined" |
| Color associated with the cluster. | |
| Eigen::Vector4f | _centroid_ |
| Centroid of the cluster. | |
| Eigen::Vector4f | _center_ |
| Center of the cone's cluster. | |
| bool | _centroid_is_defined_ = false |
| Flag indicating whether the centroid is defined or not. | |
| bool | _center_is_defined_ = false |
| Flag indicating whether the center is defined or not. | |
| double | _confidence_ = 0 |
| Confidence on the cluster to be (or not) a cone. | |
| double | _z_score_x_ = 0 |
| double | _z_score_y_ = 0 |
| bool | _is_large_ = false |
| Flag indicating the size of the cluster : | |
Static Private Attributes | |
| static constexpr auto | center_calculator |
| Calculates the center of the cone. | |
| static constexpr auto | centroid_calculator |
| Calculates the centroid of the cluster. | |
Represents a cluster of 3D points using PCL (Point Cloud Library).
Definition at line 14 of file cluster.hpp.
|
explicit |
Constructor for the Cluster class.
Definition at line 3 of file cluster.cpp.
|
static |
Calculates the mean and standard deviation on x and y axis.
| clusters | Clusters to apply get the statistical values |
Definition at line 69 of file cluster.cpp.

| Eigen::Vector4f Cluster::get_center | ( | Plane & | plane | ) |
Get the Center of the cone's cluster.
Definition at line 18 of file cluster.cpp.
| Eigen::Vector4f Cluster::get_centroid | ( | ) |
Get the centroid of the cluster.
Definition at line 7 of file cluster.cpp.

| std::string Cluster::get_color | ( | ) |
Get the color associated with the cluster.
Definition at line 30 of file cluster.cpp.

| double Cluster::get_confidence | ( | ) |
Get the Confidence of the cluster to be (or not to be) a cone.
Definition at line 52 of file cluster.cpp.
| bool Cluster::get_is_large | ( | ) |
Get cluster's corresponding cone size.
Definition at line 101 of file cluster.cpp.

| const sensor_msgs::msg::PointCloud2::SharedPtr & Cluster::get_point_cloud | ( | ) |
Get the Point Cloud data of the cluster.
Definition at line 46 of file cluster.cpp.

| const std::vector< int > & Cluster::get_point_indices | ( | ) |
Get the Point Cloud data of the cluster.
Definition at line 44 of file cluster.cpp.

| double Cluster::get_z_score_x | ( | ) | const |
Get the z score on x-axis of an object.
Definition at line 65 of file cluster.cpp.
| double Cluster::get_z_score_y | ( | ) | const |
Get the z score on y-axis of an object.
Definition at line 67 of file cluster.cpp.
| void Cluster::set_color | ( | const std::string & | new_color | ) |
Set the color for the cluster.
| new_color | The new color to be set. |
Definition at line 32 of file cluster.cpp.

| void Cluster::set_confidence | ( | double | newConfidence | ) |
Set the Confidence of the cluster to be or not to be a cone.
| newConfidence | The new Confidence of the cluster |
Definition at line 50 of file cluster.cpp.
| void Cluster::set_is_large | ( | ) |
Set cluster as a contender for a large cone.
Definition at line 103 of file cluster.cpp.

| void Cluster::set_point_indices | ( | const std::vector< int > & | new_point_indices | ) |
Set the Point Cloud data for the cluster.
| new_point_cloud | Pointer to the new Point Cloud data. |
Definition at line 38 of file cluster.cpp.
| void Cluster::set_z_score | ( | double | mean_x, |
| double | std_dev_x, | ||
| double | mean_y, | ||
| double | std_dev_y | ||
| ) |
Set the z score object on the x and y axis.
| mean_x | Mean of the x on the point's distribution |
| std_dev_x | Standard Deviation of the x on the point's distribution |
| mean_y | Mean of the y on the point's distribution |
| std_dev_y | Standard Deviation of the y on the point's distribution |
Definition at line 54 of file cluster.cpp.

|
static |
Set the z scores object on every cluster of the vector.
| clusters | Vector of clusters in which the a-scores will be applied individually |
Definition at line 94 of file cluster.cpp.


|
private |
Center of the cone's cluster.
Definition at line 137 of file cluster.hpp.
|
private |
Flag indicating whether the center is defined or not.
Definition at line 139 of file cluster.hpp.
|
private |
Centroid of the cluster.
Definition at line 136 of file cluster.hpp.
|
private |
Flag indicating whether the centroid is defined or not.
Definition at line 138 of file cluster.hpp.
|
private |
Color associated with the cluster.
Definition at line 135 of file cluster.hpp.
|
private |
Confidence on the cluster to be (or not) a cone.
Definition at line 140 of file cluster.hpp.
|
private |
Flag indicating the size of the cluster :
true = large cluster. false = small = cluster.
Definition at line 143 of file cluster.hpp.
|
private |
Point cloud data for the cluster.
Definition at line 133 of file cluster.hpp.
|
private |
Indices of points in the cluster.
Definition at line 134 of file cluster.hpp.
|
private |
Definition at line 141 of file cluster.hpp.
|
private |
Definition at line 142 of file cluster.hpp.
|
staticconstexprprivate |
Calculates the center of the cone.
Definition at line 147 of file cluster.hpp.
|
staticconstexprprivate |
Calculates the centroid of the cluster.
Definition at line 149 of file cluster.hpp.