Skip to content

Commit 7cc1c20

Browse files
committed
remove useless dependencies
1 parent 821b9f4 commit 7cc1c20

File tree

11 files changed

+67
-65
lines changed

11 files changed

+67
-65
lines changed

CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ find_package(rclpy REQUIRED)
2424
find_package(sensor_msgs REQUIRED)
2525
find_package(tf2 REQUIRED)
2626
find_package(tf2_ros REQUIRED)
27-
find_package(turtlebot3_msgs REQUIRED)
27+
# find_package(turtlebot3_msgs REQUIRED)
2828
find_package(gmm_msgs REQUIRED)
2929
find_package(gaussian_mixture_model REQUIRED)
3030
find_package(visualization_msgs REQUIRED)

include/gmm_coverage/Graphics.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@
1111
// My includes
1212
#include "Voronoi.h"
1313
#include "Vettore.h"
14-
#include "turtlebot3_msgs/msg/gmm.hpp"
14+
#include "gmm_msgs/msg/gmm.hpp"
1515

1616
//Color points/sites
1717
const uint8_t P_RED = 100; //[0-255]
@@ -433,7 +433,7 @@ class Graphics
433433
}
434434
}
435435

436-
void drawGMM(const turtlebot3_msgs::msg::GMM& gmm){
436+
void drawGMM(const gmm_msgs::msg::GMM& gmm){
437437
for (std::size_t i = 0; i < gmm.gaussians.size(); ++i){
438438
sf::CircleShape circle(0.75*POINT_RADIUS);
439439
circle.setFillColor(sf::Color(255,255,102));

include/gmm_coverage/Voronoi.h

Lines changed: 15 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -10,10 +10,10 @@
1010
#include "FortuneAlgorithm.h"
1111
#include "Utility.h"
1212
#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"
1717

1818

1919
#define M_PI 3.14159265358979323846 /*pi*/
@@ -22,11 +22,11 @@
2222

2323
float gauss3d_pdf(std::vector<float> mean, std::vector<std::vector<float>> var, std::vector<float> pt);
2424
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);
3030

3131
//***********************************************************************************************************************************
3232
//-------------------------------- FUNZIONI AUSILIARIE INIZIALI (trasformazione coordinate + sensing) ---------------------------------
@@ -1198,10 +1198,10 @@ std::vector<float> computeGMMPolygonCentroid(const Diagram<double> &polygon, std
11981198
}
11991199

12001200
// 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){
12021202

12031203
// Transform GMM to local coordinates
1204-
turtlebot3_msgs::msg::GMM gmm_local;
1204+
gmm_msgs::msg::GMM gmm_local;
12051205
gmm_local.weights = gmm.weights;
12061206
for (long unsigned int i = 0; i < gmm.gaussians.size(); ++i)
12071207
{
@@ -1455,7 +1455,7 @@ float gauss3d_pdf(std::vector<float> mean, std::vector<std::vector<float>> var,
14551455
return prob;
14561456
}
14571457

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){
14591459
std::vector<float> mean = {}; // mean vector (1D, 2D or 3D)
14601460
std::vector<std::vector<float>> var = {}; // covariance matrix
14611461
std::vector<float> row = {}; // covariance matrix rows
@@ -1527,7 +1527,7 @@ float gauss3d_pdf2(turtlebot3_msgs::msg::Gaussian gaussian, std::vector<float> p
15271527
}
15281528

15291529

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){
15311531
// std::cout << "Entered single component pdf" << std::endl;
15321532
Eigen::VectorXd mean_pt;
15331533
Eigen::MatrixXd cov_matrix;
@@ -1602,7 +1602,7 @@ float single_component_pdf(turtlebot3_msgs::msg::Gaussian gaussian, std::vector<
16021602
}
16031603

16041604

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)
16061606
{
16071607
// std::cout << "Entered multi-component pdf" << std::endl;
16081608
float val = 0;
@@ -1685,7 +1685,7 @@ float multiple_gauss3d_pdf(std::vector<std::vector<float>> means_pt, std::vector
16851685
}
16861686

16871687
//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){
16891689
float val = 0;
16901690

16911691
// devo avere stesso numero di punti medi, varianze e pesi

scripts/interface.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@
99
# ROS imports
1010
import rclpy
1111
from rclpy.node import Node
12-
from turtlebot3_msgs.msg import GMM, Gaussian
12+
from gmm_msgs.msg import GMM, Gaussian
1313
from geometry_msgs.msg import Point
1414
from ament_index_python.packages import get_package_prefix
1515

src/centralized_gmm.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -44,8 +44,8 @@
4444
#include <geometry_msgs/msg/twist.hpp>
4545
#include <geometry_msgs/msg/pose_stamped.hpp>
4646
#include <nav_msgs/msg/odometry.hpp>
47-
#include "turtlebot3_msgs/msg/gaussian.hpp"
48-
#include "turtlebot3_msgs/msg/gmm.hpp"
47+
#include "gmm_msgs/msg/gaussian.hpp"
48+
#include "gmm_msgs/msg/gmm.hpp"
4949

5050
#define M_PI 3.14159265358979323846 /*pi*/
5151

@@ -132,7 +132,7 @@ class Controller : public rclcpp::Node
132132
}
133133
}
134134
joySub_ = this->create_subscription<geometry_msgs::msg::Twist>("/joy_vel", 1, std::bind(&Controller::joy_callback, this, _1));
135-
gmmSub_ = this->create_subscription<turtlebot3_msgs::msg::GMM>("/gaussian_mixture_model", 1, std::bind(&Controller::gmm_callback, this, _1));
135+
gmmSub_ = this->create_subscription<gmm_msgs::msg::GMM>("/gaussian_mixture_model", 1, std::bind(&Controller::gmm_callback, this, _1));
136136
timer_ = this->create_wall_timer(500ms, std::bind(&Controller::Formation, this));
137137
//rclcpp::on_shutdown(std::bind(&Controller::stop,this));
138138

@@ -162,7 +162,7 @@ class Controller : public rclcpp::Node
162162
void odomCallback(const nav_msgs::msg::Odometry::SharedPtr msg, int j);
163163
void poseCallback(const geometry_msgs::msg::PoseStamped::SharedPtr msg, int j);
164164
void joy_callback(const geometry_msgs::msg::Twist::SharedPtr msg);
165-
void gmm_callback(const turtlebot3_msgs::msg::GMM::SharedPtr msg);
165+
void gmm_callback(const gmm_msgs::msg::GMM::SharedPtr msg);
166166
Eigen::VectorXd Matrix_row_sum(Eigen::MatrixXd x);
167167
Eigen::MatrixXd Diag_Matrix(Eigen::VectorXd V);
168168
void Formation();
@@ -195,9 +195,9 @@ class Controller : public rclcpp::Node
195195
std::vector<rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr> poseSub_;
196196
std::vector<rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr> odomSub_;
197197
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr joySub_;
198-
rclcpp::Subscription<turtlebot3_msgs::msg::GMM>::SharedPtr gmmSub_;
198+
rclcpp::Subscription<gmm_msgs::msg::GMM>::SharedPtr gmmSub_;
199199
rclcpp::TimerBase::SharedPtr timer_;
200-
turtlebot3_msgs::msg::GMM gmm_msg;
200+
gmm_msgs::msg::GMM gmm_msg;
201201
//-----------------------------------------------------------------------------------
202202

203203
//Rendering with SFML
@@ -311,7 +311,7 @@ void Controller::joy_callback(const geometry_msgs::msg::Twist::SharedPtr msg)
311311
this->vel_angular_z = msg->angular.z;
312312
}
313313

314-
void Controller::gmm_callback(const turtlebot3_msgs::msg::GMM::SharedPtr msg)
314+
void Controller::gmm_callback(const gmm_msgs::msg::GMM::SharedPtr msg)
315315
{
316316
// std::cout << "ROBOT " << std::to_string(ID) << " dentro a GMM callback" << std::endl;
317317
this->gmm_msg.gaussians = msg->gaussians;

src/distributed_gmm.cpp

Lines changed: 9 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -47,8 +47,10 @@
4747
#include <geometry_msgs/msg/polygon.hpp>
4848
#include <geometry_msgs/msg/polygon_stamped.hpp>
4949
#include <nav_msgs/msg/odometry.hpp>
50-
#include "turtlebot3_msgs/msg/gaussian.hpp"
51-
#include "turtlebot3_msgs/msg/gmm.hpp"
50+
// #include "gmm_msgs/msg/gaussian.hpp"
51+
// #include "gmm_msgs/msg/gmm.hpp"
52+
#include "gmm_msgs/msg/gaussian.hpp"
53+
#include "gmm_msgs/msg/gmm.hpp"
5254

5355
#define M_PI 3.14159265358979323846 /*pi*/
5456

@@ -136,7 +138,7 @@ class Controller : public rclcpp::Node
136138
}
137139

138140
joySub_ = this->create_subscription<geometry_msgs::msg::Twist>("/joy_vel", 1, std::bind(&Controller::joy_callback, this, _1));
139-
gmmSub_ = this->create_subscription<turtlebot3_msgs::msg::GMM>("/gaussian_mixture_model", 1, std::bind(&Controller::gmm_callback, this, _1));
141+
gmmSub_ = this->create_subscription<gmm_msgs::msg::GMM>("/gaussian_mixture_model", 1, std::bind(&Controller::gmm_callback, this, _1));
140142
voronoiPub = this->create_publisher<geometry_msgs::msg::PolygonStamped>("/voronoi"+std::to_string(ID)+"_diagram", 1);
141143
timer_ = this->create_wall_timer(200ms, std::bind(&Controller::Formation, this));
142144
//rclcpp::on_shutdown(std::bind(&Controller::stop,this));
@@ -160,7 +162,7 @@ class Controller : public rclcpp::Node
160162
void odomCallback(const nav_msgs::msg::Odometry::SharedPtr msg, int j);
161163
void poseCallback(const geometry_msgs::msg::PoseStamped::SharedPtr msg, int j);
162164
void joy_callback(const geometry_msgs::msg::Twist::SharedPtr msg);
163-
void gmm_callback(const turtlebot3_msgs::msg::GMM::SharedPtr msg);
165+
void gmm_callback(const gmm_msgs::msg::GMM::SharedPtr msg);
164166
void Formation();
165167
geometry_msgs::msg::Twist Diff_drive_compute_vel(double vel_x, double vel_y, double alfa);
166168

@@ -194,10 +196,10 @@ class Controller : public rclcpp::Node
194196
std::vector<rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr> poseSub_;
195197
std::vector<rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr> odomSub_;
196198
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr joySub_;
197-
rclcpp::Subscription<turtlebot3_msgs::msg::GMM>::SharedPtr gmmSub_;
199+
rclcpp::Subscription<gmm_msgs::msg::GMM>::SharedPtr gmmSub_;
198200
rclcpp::Publisher<geometry_msgs::msg::PolygonStamped>::SharedPtr voronoiPub;
199201
rclcpp::TimerBase::SharedPtr timer_;
200-
turtlebot3_msgs::msg::GMM gmm_msg;
202+
gmm_msgs::msg::GMM gmm_msg;
201203
geometry_msgs::msg::Polygon polygon_msg;
202204
geometry_msgs::msg::PolygonStamped polygonStamped_msg;
203205

@@ -307,7 +309,7 @@ void Controller::joy_callback(const geometry_msgs::msg::Twist::SharedPtr msg)
307309
this->vel_angular_z = msg->angular.z;
308310
}
309311

310-
void Controller::gmm_callback(const turtlebot3_msgs::msg::GMM::SharedPtr msg)
312+
void Controller::gmm_callback(const gmm_msgs::msg::GMM::SharedPtr msg)
311313
{
312314
this->gmm_msg.gaussians = msg->gaussians;
313315
this->gmm_msg.weights = msg->weights;

src/gmm_calc.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -33,8 +33,8 @@
3333
#include <geometry_msgs/msg/pose.hpp>
3434
#include <geometry_msgs/msg/point.hpp>
3535
#include <nav_msgs/msg/odometry.hpp>
36-
#include "turtlebot3_msgs/msg/gaussian.hpp"
37-
#include "turtlebot3_msgs/msg/gmm.hpp"
36+
#include "gmm_msgs/msg/gaussian.hpp"
37+
#include "gmm_msgs/msg/gmm.hpp"
3838
#include <visualization_msgs/msg/marker.hpp>
3939
#include <visualization_msgs/msg/marker_array.hpp>
4040

@@ -77,7 +77,7 @@ class Supervisor : public rclcpp::Node
7777
//-----------------------------------------------------------------------------------------------------------------------------------
7878

7979
//------------------------------------------------- ROS publishers and subscribers -------------------------------------------------
80-
gmm_pub_ = this->create_publisher<turtlebot3_msgs::msg::GMM>("/gaussian_mixture_model_"+std::to_string(ID), 10);
80+
gmm_pub_ = this->create_publisher<gmm_msgs::msg::GMM>("/gaussian_mixture_model_"+std::to_string(ID), 10);
8181
odom_sub_ = this->create_subscription<nav_msgs::msg::Odometry>("turtlebot" + std::to_string(ID) + "/odom", 1, std::bind(&Supervisor::odomCallback, this, _1));
8282
for (int i = 0; i < TARGETS_NUM; i++)
8383
{
@@ -181,7 +181,7 @@ class Supervisor : public rclcpp::Node
181181
Eigen::MatrixXd p_j;
182182
std::vector<Eigen::VectorXd> targets_real;
183183

184-
rclcpp::Publisher<turtlebot3_msgs::msg::GMM>::SharedPtr gmm_pub_;
184+
rclcpp::Publisher<gmm_msgs::msg::GMM>::SharedPtr gmm_pub_;
185185
std::vector<rclcpp::Subscription<geometry_msgs::msg::Pose>::SharedPtr> target_subs_;
186186
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr odom_sub_;
187187
std::vector<rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr> neighbor_subs_;
@@ -325,12 +325,12 @@ void Supervisor::loop()
325325
// }
326326

327327
// Create ROS GMM msg
328-
turtlebot3_msgs::msg::GMM gmm_msg;
328+
gmm_msgs::msg::GMM gmm_msg;
329329
gmm_msg.weights = weights;
330330

331331
for(int i = 0; i < mean_points.size(); i++)
332332
{
333-
turtlebot3_msgs::msg::Gaussian gaussian;
333+
gmm_msgs::msg::Gaussian gaussian;
334334
gaussian.mean_point.x = mean_points[i](0);
335335
gaussian.mean_point.y = mean_points[i](1);
336336
gaussian.covariance.push_back(covariances[i](0,0));

src/gmm_test_node.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -26,8 +26,8 @@
2626

2727

2828
#include "rclcpp/rclcpp.hpp"
29-
#include "turtlebot3_msgs/msg/gaussian.hpp"
30-
#include "turtlebot3_msgs/msg/gmm.hpp"
29+
#include "gmm_msgs/msg/gaussian.hpp"
30+
#include "gmm_msgs/msg/gmm.hpp"
3131

3232

3333
#include "gaussian_mixture_model/gaussian_mixture_model.h"
@@ -45,8 +45,8 @@ class GMM_Test : public rclcpp::Node
4545

4646
// ROS Related Variables
4747
rclcpp::TimerBase::SharedPtr timer_;
48-
turtlebot3_msgs::msg::GMM gmm_msg;
49-
rclcpp::Publisher<turtlebot3_msgs::msg::GMM>::SharedPtr gmm_pub_;
48+
gmm_msgs::msg::GMM gmm_msg;
49+
rclcpp::Publisher<gmm_msgs::msg::GMM>::SharedPtr gmm_pub_;
5050

5151
public:
5252

@@ -57,7 +57,7 @@ class GMM_Test : public rclcpp::Node
5757

5858
// Initialize ROS variables
5959
timer_ = this->create_wall_timer(std::chrono::milliseconds(100), std::bind(&GMM_Test::timerCallback, this));
60-
gmm_pub_ = this->create_publisher<turtlebot3_msgs::msg::GMM>("/gaussian_mixture_model", 10);
60+
gmm_pub_ = this->create_publisher<gmm_msgs::msg::GMM>("/gaussian_mixture_model", 10);
6161

6262
samples.resize(2,200);
6363
double dev = 0.5;
@@ -150,7 +150,7 @@ class GMM_Test : public rclcpp::Node
150150

151151
for(int i = 0; i < mean_points.size(); i++)
152152
{
153-
turtlebot3_msgs::msg::Gaussian gaussian;
153+
gmm_msgs::msg::Gaussian gaussian;
154154
gaussian.mean_point.x = mean_points[i](0);
155155
gaussian.mean_point.y = mean_points[i](1);
156156
gaussian.covariance.push_back(covariances[i](0,0));

src/gmm_visualizer.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -45,8 +45,8 @@
4545
#include <nav_msgs/msg/odometry.hpp>
4646
#include <visualization_msgs/msg/marker.hpp>
4747
#include <visualization_msgs/msg/marker_array.hpp>
48-
#include "turtlebot3_msgs/msg/gaussian.hpp"
49-
#include "turtlebot3_msgs/msg/gmm.hpp"
48+
#include "gmm_msgs/msg/gaussian.hpp"
49+
#include "gmm_msgs/msg/gmm.hpp"
5050

5151
#define M_PI 3.14159265358979323846 /*pi*/
5252

@@ -67,15 +67,15 @@ class Visualizer : public rclcpp::Node
6767
// --------------------------------------------------------- GMM ROS publishers and subscribers -------------------------------------------------------
6868
publisher = this->create_publisher<visualization_msgs::msg::MarkerArray>("/gmm_markers", 1);
6969
timer_ = this->create_wall_timer(1000ms, std::bind(&Visualizer::show, this));
70-
gmmSub_ = this->create_subscription<turtlebot3_msgs::msg::GMM>("/gaussian_mixture_model", 1, std::bind(&Visualizer::gmm_callback, this, _1));
70+
gmmSub_ = this->create_subscription<gmm_msgs::msg::GMM>("/gaussian_mixture_model", 1, std::bind(&Visualizer::gmm_callback, this, _1));
7171

7272
}
7373
~Visualizer()
7474
{
7575
std::cout<<"DESTROYER HAS BEEN CALLED"<<std::endl;
7676
}
7777

78-
void gmm_callback(const turtlebot3_msgs::msg::GMM::SharedPtr msg);
78+
void gmm_callback(const gmm_msgs::msg::GMM::SharedPtr msg);
7979
void GroundColorMix(double* color, double x, double min, double max);
8080
void show();
8181

@@ -91,15 +91,15 @@ class Visualizer : public rclcpp::Node
9191
//------------------------- Publishers and subscribers ------------------------------
9292
rclcpp::TimerBase::SharedPtr timer_;
9393
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr publisher;
94-
rclcpp::Subscription<turtlebot3_msgs::msg::GMM>::SharedPtr gmmSub_;
95-
turtlebot3_msgs::msg::GMM gmm_msg;
94+
rclcpp::Subscription<gmm_msgs::msg::GMM>::SharedPtr gmmSub_;
95+
gmm_msgs::msg::GMM gmm_msg;
9696
visualization_msgs::msg::MarkerArray markers_msg;
9797
std::vector<visualization_msgs::msg::Marker> markers_array;
9898
//-----------------------------------------------------------------------------------
9999

100100
};
101101

102-
void Visualizer::gmm_callback(const turtlebot3_msgs::msg::GMM::SharedPtr msg)
102+
void Visualizer::gmm_callback(const gmm_msgs::msg::GMM::SharedPtr msg)
103103
{
104104
this->gmm_msg.gaussians = msg->gaussians;
105105
this->gmm_msg.weights = msg->weights;

src/hs_interface.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -43,8 +43,8 @@
4343
#include <geometry_msgs/msg/twist.hpp>
4444
#include <geometry_msgs/msg/pose_stamped.hpp>
4545
#include <nav_msgs/msg/odometry.hpp>
46-
#include "turtlebot3_msgs/msg/gaussian.hpp"
47-
#include "turtlebot3_msgs/msg/gmm.hpp"
46+
#include "gmm_msgs/msg/gaussian.hpp"
47+
#include "gmm_msgs/msg/gmm.hpp"
4848
// #include <GaussianMixtureModel/GaussianMixtureModel.h>
4949
// #include <GaussianMixtureModel/ExpectationMaximization.h>
5050
// #include <GaussianMixtureModel/TrainSet.h>
@@ -82,7 +82,7 @@ class Interface : public rclcpp::Node
8282
this->get_parameter("PARTICLES_NUM", PARTICLES_NUM);
8383

8484
// --------------------------------------------------------- GMM ROS publisher -------------------------------------------------------
85-
publisher = this->create_publisher<turtlebot3_msgs::msg::GMM>("/gaussian_mixture_model", 1);
85+
publisher = this->create_publisher<gmm_msgs::msg::GMM>("/gaussian_mixture_model", 1);
8686
timer_ = this->create_wall_timer(100ms, std::bind(&Interface::timer_callback, this));
8787

8888
//----------------------------------------------------------- init Variables ---------------------------------------------------------
@@ -124,7 +124,7 @@ class Interface : public rclcpp::Node
124124

125125
for(int i = 0; i < mean_points.size(); i++)
126126
{
127-
turtlebot3_msgs::msg::Gaussian gaussian;
127+
gmm_msgs::msg::Gaussian gaussian;
128128
gaussian.mean_point.x = mean_points[i](0);
129129
gaussian.mean_point.y = mean_points[i](1);
130130
gaussian.covariance.push_back(covariances[i](0,0));
@@ -165,8 +165,8 @@ class Interface : public rclcpp::Node
165165
Eigen::MatrixXd samples;
166166
//------------------------- Publishers and subscribers ------------------------------
167167
rclcpp::TimerBase::SharedPtr timer_;
168-
rclcpp::Publisher<turtlebot3_msgs::msg::GMM>::SharedPtr publisher;
169-
turtlebot3_msgs::msg::GMM gmm_msg;
168+
rclcpp::Publisher<gmm_msgs::msg::GMM>::SharedPtr publisher;
169+
gmm_msgs::msg::GMM gmm_msg;
170170
//-----------------------------------------------------------------------------------
171171

172172
// SFML GUI

0 commit comments

Comments
 (0)