diff --git a/hand_control/launch/all.launch b/hand_control/launch/all.launch
index 5cfd6a4..cb118bc 100644
--- a/hand_control/launch/all.launch
+++ b/hand_control/launch/all.launch
@@ -2,11 +2,11 @@
-
-
-
+
+
+
diff --git a/hand_control/launch/essai-filtre.launch b/hand_control/launch/essai-filtre.launch
index b727328..280b9b4 100644
--- a/hand_control/launch/essai-filtre.launch
+++ b/hand_control/launch/essai-filtre.launch
@@ -1,9 +1,14 @@
-
+
-
+
+
+
-
+
+
+
+
diff --git a/hand_control/src/filtre.cpp b/hand_control/src/filtre.cpp
index ec6c88b..fcde972 100644
--- a/hand_control/src/filtre.cpp
+++ b/hand_control/src/filtre.cpp
@@ -52,7 +52,7 @@ int
main(int argc, char** argv)
{
ros::init(argc, argv, "filtre");
- ros::NodeHandle node;
+ ros::NodeHandle node("filtre");
// récupération des paramètres
double zmax(0);
@@ -66,9 +66,9 @@ main(int argc, char** argv)
}
// initialisation
- ros::Publisher publisher = node.advertise("filtre_output", 1);
+ ros::Publisher publisher = node.advertise("output", 1);
Callback callback(publisher);
- ros::Subscriber subscriber = node.subscribe("filtre_input", 1, callback);
+ ros::Subscriber subscriber = node.subscribe("input", 1, callback);
// démarrage
ROS_INFO("node started");
diff --git a/hand_control/src/random_pcl_publisher.cpp b/hand_control/src/random_pcl_publisher.cpp
index 8cd77f9..1d2d2c6 100644
--- a/hand_control/src/random_pcl_publisher.cpp
+++ b/hand_control/src/random_pcl_publisher.cpp
@@ -85,7 +85,7 @@ main(int argc, char** argv)
ROS_INFO("length : %d (default value)", length);
}
// initialisation
- ros::Publisher publisher = node.advertise("random_output", 1);
+ ros::Publisher publisher = node.advertise("output", 1);
Generator generator(length, min, max);
ros::Rate loop_rate(freq);
ROS_INFO("node started");