noms des topics plus simples

This commit is contained in:
Louis-Guillaume DUBOIS 2015-04-23 12:29:04 +02:00
parent e553dc0e8f
commit 39273e79ab
4 changed files with 15 additions and 10 deletions

View file

@ -3,10 +3,10 @@
<include file="$(find hand_control)/launch/freenect-registered-xyzrgb.launch"/>
<param name="zmax" value="50.0" type="double"/>
<node name="filtre_z" pkg="hand_control" type="filtre">
<remap from="filtre_input" to="/camera/xyzrgb/points"/>
<remap from="/filtre/input" to="/camera/xyzrgb/points"/>
</node>
<param name="/filtre/zmax" value="50.0" type="double"/>
</launch>

View file

@ -1,9 +1,14 @@
<launch>
<param name="zmax" value="100." type="double" />
<node name="filtre_z" pkg="hand_control" type="filtre">
<remap from="filtre_input" to="random_pcl"/>
<remap from="/filtre/input" to="random_pcl"/>
</node>
<param name="/filtre/zmax" value="100." type="double" />
<node name="publisher" pkg="hand_control" type="random_pcl_publisher" >
<remap from="random_output" to="random_pcl"/>
<remap from="/random/output" to="random_pcl"/>
</node>
<param name="/random/freq" value="1." type="double" />
<param name="/random/length" value="5" type="int" />
</launch>

View file

@ -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<PointCloud>("filtre_output", 1);
ros::Publisher publisher = node.advertise<PointCloud>("output", 1);
Callback callback(publisher);
ros::Subscriber subscriber = node.subscribe<PointCloud>("filtre_input", 1, callback);
ros::Subscriber subscriber = node.subscribe<PointCloud>("input", 1, callback);
// démarrage
ROS_INFO("node started");

View file

@ -85,7 +85,7 @@ main(int argc, char** argv)
ROS_INFO("length : %d (default value)", length);
}
// initialisation
ros::Publisher publisher = node.advertise<PointCloud>("random_output", 1);
ros::Publisher publisher = node.advertise<PointCloud>("output", 1);
Generator generator(length, min, max);
ros::Rate loop_rate(freq);
ROS_INFO("node started");