|
10 | 10 | #include "FortuneAlgorithm.h" |
11 | 11 | #include "Utility.h" |
12 | 12 | #include <iostream> |
13 | | -// #include "/home/mattia/arscontrol_turtlebot/install/turtlebot3_msgs/include/turtlebot3_msgs/msg/gmm.hpp" |
14 | | -// #include "/home/mattia/arscontrol_turtlebot/install/turtlebot3_msgs/include/turtlebot3_msgs/msg/gaussian.hpp" |
15 | | -#include "turtlebot3_msgs/msg/gmm.hpp" |
16 | | -#include "turtlebot3_msgs/msg/gaussian.hpp" |
| 13 | +// #include "/home/mattia/arscontrol_turtlebot/install/gmm_msgs/include/gmm_msgs/msg/gmm.hpp" |
| 14 | +// #include "/home/mattia/arscontrol_turtlebot/install/gmm_msgs/include/gmm_msgs/msg/gaussian.hpp" |
| 15 | +#include "gmm_msgs/msg/gmm.hpp" |
| 16 | +#include "gmm_msgs/msg/gaussian.hpp" |
17 | 17 |
|
18 | 18 |
|
19 | 19 | #define M_PI 3.14159265358979323846 /*pi*/ |
|
22 | 22 |
|
23 | 23 | float gauss3d_pdf(std::vector<float> mean, std::vector<std::vector<float>> var, std::vector<float> pt); |
24 | 24 | float multiple_gauss3d_pdf(std::vector<std::vector<float>> means_pt, std::vector<std::vector<std::vector<float>>> vars, std::vector<float> pt, std::vector<float> weights); |
25 | | -float gauss3d_pdf2(turtlebot3_msgs::msg::Gaussian gaussian, std::vector<float> pt); |
26 | | -float multiple_gauss3d_pdf2(turtlebot3_msgs::msg::GMM gmm, std::vector<float> pt); |
27 | | -float single_component_pdf(turtlebot3_msgs::msg::Gaussian gaussian, std::vector<float> pt); |
28 | | -float mixture_pdf(turtlebot3_msgs::msg::GMM gmm, std::vector<float> pt); |
29 | | -std::vector<float> computeGMMPolygonCentroid2(const Diagram<double> &polygon, turtlebot3_msgs::msg::GMM gmm, std::vector<Box<double>> ObstacleBoxes, float discretize_precision); |
| 25 | +float gauss3d_pdf2(gmm_msgs::msg::Gaussian gaussian, std::vector<float> pt); |
| 26 | +float multiple_gauss3d_pdf2(gmm_msgs::msg::GMM gmm, std::vector<float> pt); |
| 27 | +float single_component_pdf(gmm_msgs::msg::Gaussian gaussian, std::vector<float> pt); |
| 28 | +float mixture_pdf(gmm_msgs::msg::GMM gmm, std::vector<float> pt); |
| 29 | +std::vector<float> computeGMMPolygonCentroid2(const Diagram<double> &polygon, gmm_msgs::msg::GMM gmm, std::vector<Box<double>> ObstacleBoxes, float discretize_precision); |
30 | 30 |
|
31 | 31 | //*********************************************************************************************************************************** |
32 | 32 | //-------------------------------- FUNZIONI AUSILIARIE INIZIALI (trasformazione coordinate + sensing) --------------------------------- |
@@ -1198,10 +1198,10 @@ std::vector<float> computeGMMPolygonCentroid(const Diagram<double> &polygon, std |
1198 | 1198 | } |
1199 | 1199 |
|
1200 | 1200 | // Funzione per il calcolo del centroide in caso di GMM definite con messaggio custom |
1201 | | -std::vector<float> computeGMMPolygonCentroid2(const Diagram<double> &polygon, turtlebot3_msgs::msg::GMM gmm, std::vector<Box<double>> ObstacleBoxes = {}, float discretize_precision = 1.0/10.0){ |
| 1201 | +std::vector<float> computeGMMPolygonCentroid2(const Diagram<double> &polygon, gmm_msgs::msg::GMM gmm, std::vector<Box<double>> ObstacleBoxes = {}, float discretize_precision = 1.0/10.0){ |
1202 | 1202 |
|
1203 | 1203 | // Transform GMM to local coordinates |
1204 | | - turtlebot3_msgs::msg::GMM gmm_local; |
| 1204 | + gmm_msgs::msg::GMM gmm_local; |
1205 | 1205 | gmm_local.weights = gmm.weights; |
1206 | 1206 | for (long unsigned int i = 0; i < gmm.gaussians.size(); ++i) |
1207 | 1207 | { |
@@ -1455,7 +1455,7 @@ float gauss3d_pdf(std::vector<float> mean, std::vector<std::vector<float>> var, |
1455 | 1455 | return prob; |
1456 | 1456 | } |
1457 | 1457 |
|
1458 | | -float gauss3d_pdf2(turtlebot3_msgs::msg::Gaussian gaussian, std::vector<float> pt){ |
| 1458 | +float gauss3d_pdf2(gmm_msgs::msg::Gaussian gaussian, std::vector<float> pt){ |
1459 | 1459 | std::vector<float> mean = {}; // mean vector (1D, 2D or 3D) |
1460 | 1460 | std::vector<std::vector<float>> var = {}; // covariance matrix |
1461 | 1461 | std::vector<float> row = {}; // covariance matrix rows |
@@ -1527,7 +1527,7 @@ float gauss3d_pdf2(turtlebot3_msgs::msg::Gaussian gaussian, std::vector<float> p |
1527 | 1527 | } |
1528 | 1528 |
|
1529 | 1529 |
|
1530 | | -float single_component_pdf(turtlebot3_msgs::msg::Gaussian gaussian, std::vector<float> pt){ |
| 1530 | +float single_component_pdf(gmm_msgs::msg::Gaussian gaussian, std::vector<float> pt){ |
1531 | 1531 | // std::cout << "Entered single component pdf" << std::endl; |
1532 | 1532 | Eigen::VectorXd mean_pt; |
1533 | 1533 | Eigen::MatrixXd cov_matrix; |
@@ -1602,7 +1602,7 @@ float single_component_pdf(turtlebot3_msgs::msg::Gaussian gaussian, std::vector< |
1602 | 1602 | } |
1603 | 1603 |
|
1604 | 1604 |
|
1605 | | -float mixture_pdf(turtlebot3_msgs::msg::GMM gmm, std::vector<float> pt) |
| 1605 | +float mixture_pdf(gmm_msgs::msg::GMM gmm, std::vector<float> pt) |
1606 | 1606 | { |
1607 | 1607 | // std::cout << "Entered multi-component pdf" << std::endl; |
1608 | 1608 | float val = 0; |
@@ -1685,7 +1685,7 @@ float multiple_gauss3d_pdf(std::vector<std::vector<float>> means_pt, std::vector |
1685 | 1685 | } |
1686 | 1686 |
|
1687 | 1687 | //funzione per calcolare il valore di un punto dato un Gaussian Mixture Model |
1688 | | -float multiple_gauss3d_pdf2(turtlebot3_msgs::msg::GMM gmm, std::vector<float> pt){ |
| 1688 | +float multiple_gauss3d_pdf2(gmm_msgs::msg::GMM gmm, std::vector<float> pt){ |
1689 | 1689 | float val = 0; |
1690 | 1690 |
|
1691 | 1691 | // devo avere stesso numero di punti medi, varianze e pesi |
|
0 commit comments