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

Represents a cluster of 3D points using PCL (Point Cloud Library). More...

#include <cluster.hpp>

Collaboration diagram for Cluster:
Collaboration graph

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.
 

Detailed Description

Represents a cluster of 3D points using PCL (Point Cloud Library).

Definition at line 14 of file cluster.hpp.

Constructor & Destructor Documentation

◆ Cluster()

Cluster::Cluster ( const sensor_msgs::msg::PointCloud2::SharedPtr &  point_cloud,
const std::vector< int > &  point_indices 
)
explicit

Constructor for the Cluster class.

Definition at line 3 of file cluster.cpp.

Member Function Documentation

◆ calculate_mean_and_std_dev()

std::tuple< double, double, double, double > Cluster::calculate_mean_and_std_dev ( std::vector< Cluster > &  clusters)
static

Calculates the mean and standard deviation on x and y axis.

Parameters
clustersClusters to apply get the statistical values
Returns
std::tuple<double, double, double, double> (mean x, mean y, standard deviation x, standard deviation y)

Definition at line 69 of file cluster.cpp.

Here is the caller graph for this function:

◆ get_center()

Eigen::Vector4f Cluster::get_center ( Plane plane)

Get the Center of the cone's cluster.

Returns
Eigen::Vector4f representing the center

Definition at line 18 of file cluster.cpp.

◆ get_centroid()

Eigen::Vector4f Cluster::get_centroid ( )

Get the centroid of the cluster.

Returns
Eigen::Vector4f representing the centroid.

Definition at line 7 of file cluster.cpp.

Here is the caller graph for this function:

◆ get_color()

std::string Cluster::get_color ( )

Get the color associated with the cluster.

Returns
std::string representing the color.

Definition at line 30 of file cluster.cpp.

Here is the caller graph for this function:

◆ get_confidence()

double Cluster::get_confidence ( )

Get the Confidence of the cluster to be (or not to be) a cone.

Returns
double Cluster's confidence

Definition at line 52 of file cluster.cpp.

◆ get_is_large()

bool Cluster::get_is_large ( )

Get cluster's corresponding cone size.

Returns
bool representing size .

Definition at line 101 of file cluster.cpp.

Here is the caller graph for this function:

◆ get_point_cloud()

const sensor_msgs::msg::PointCloud2::SharedPtr & Cluster::get_point_cloud ( )

Get the Point Cloud data of the cluster.

Returns
pcl::PointCloud<pcl::PointXYZI>::Ptr representing the Point Cloud data.

Definition at line 46 of file cluster.cpp.

Here is the caller graph for this function:

◆ get_point_indices()

const std::vector< int > & Cluster::get_point_indices ( )

Get the Point Cloud data of the cluster.

Returns
pcl::PointCloud<pcl::PointXYZI>::Ptr representing the Point Cloud data.

Definition at line 44 of file cluster.cpp.

Here is the caller graph for this function:

◆ get_z_score_x()

double Cluster::get_z_score_x ( ) const

Get the z score on x-axis of an object.

Returns
double Z-score on x axis

Definition at line 65 of file cluster.cpp.

◆ get_z_score_y()

double Cluster::get_z_score_y ( ) const

Get the z score on y-axis of an object.

Returns
double Z-score on y axis

Definition at line 67 of file cluster.cpp.

◆ set_color()

void Cluster::set_color ( const std::string &  new_color)

Set the color for the cluster.

Parameters
new_colorThe new color to be set.

Definition at line 32 of file cluster.cpp.

Here is the caller graph for this function:

◆ set_confidence()

void Cluster::set_confidence ( double  newConfidence)

Set the Confidence of the cluster to be or not to be a cone.

Parameters
newConfidenceThe new Confidence of the cluster

Definition at line 50 of file cluster.cpp.

◆ set_is_large()

void Cluster::set_is_large ( )

Set cluster as a contender for a large cone.

Definition at line 103 of file cluster.cpp.

Here is the caller graph for this function:

◆ set_point_indices()

void Cluster::set_point_indices ( const std::vector< int > &  new_point_indices)

Set the Point Cloud data for the cluster.

Parameters
new_point_cloudPointer to the new Point Cloud data.

Definition at line 38 of file cluster.cpp.

◆ set_z_score()

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.

Parameters
mean_xMean of the x on the point's distribution
std_dev_xStandard Deviation of the x on the point's distribution
mean_yMean of the y on the point's distribution
std_dev_yStandard Deviation of the y on the point's distribution

Definition at line 54 of file cluster.cpp.

Here is the call graph for this function:

◆ set_z_scores()

void Cluster::set_z_scores ( std::vector< Cluster > &  clusters)
static

Set the z scores object on every cluster of the vector.

Parameters
clustersVector of clusters in which the a-scores will be applied individually

Definition at line 94 of file cluster.cpp.

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

Member Data Documentation

◆ _center_

Eigen::Vector4f Cluster::_center_
private

Center of the cone's cluster.

Definition at line 137 of file cluster.hpp.

◆ _center_is_defined_

bool Cluster::_center_is_defined_ = false
private

Flag indicating whether the center is defined or not.

Definition at line 139 of file cluster.hpp.

◆ _centroid_

Eigen::Vector4f Cluster::_centroid_
private

Centroid of the cluster.

Definition at line 136 of file cluster.hpp.

◆ _centroid_is_defined_

bool Cluster::_centroid_is_defined_ = false
private

Flag indicating whether the centroid is defined or not.

Definition at line 138 of file cluster.hpp.

◆ _color_

std::string Cluster::_color_ = "undefined"
private

Color associated with the cluster.

Definition at line 135 of file cluster.hpp.

◆ _confidence_

double Cluster::_confidence_ = 0
private

Confidence on the cluster to be (or not) a cone.

Definition at line 140 of file cluster.hpp.

◆ _is_large_

bool Cluster::_is_large_ = false
private

Flag indicating the size of the cluster :

true = large cluster. false = small = cluster.

Definition at line 143 of file cluster.hpp.

◆ _point_cloud_

const sensor_msgs::msg::PointCloud2::SharedPtr Cluster::_point_cloud_
private

Point cloud data for the cluster.

Definition at line 133 of file cluster.hpp.

◆ _point_indices_

std::vector<int> Cluster::_point_indices_
private

Indices of points in the cluster.

Definition at line 134 of file cluster.hpp.

◆ _z_score_x_

double Cluster::_z_score_x_ = 0
private

Definition at line 141 of file cluster.hpp.

◆ _z_score_y_

double Cluster::_z_score_y_ = 0
private

Definition at line 142 of file cluster.hpp.

◆ center_calculator

constexpr auto Cluster::center_calculator
staticconstexprprivate
Initial value:
=
Concrete class representing a circumference-based method for estimating the center position of a cone...

Calculates the center of the cone.

Definition at line 147 of file cluster.hpp.

◆ centroid_calculator

constexpr auto Cluster::centroid_calculator
staticconstexprprivate
Initial value:
=
Concrete Class representing a centroid-based method for estimating the center position of a cone.

Calculates the centroid of the cluster.

Definition at line 149 of file cluster.hpp.


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