corrige r g b dans random_pcl_publisher & pcl_displayer

This commit is contained in:
Louis-Guillaume DUBOIS 2015-04-23 19:35:16 +02:00
parent d45cde8b6d
commit 46d56b3297
5 changed files with 61 additions and 23 deletions

View file

@ -1,6 +1,7 @@
cmake_minimum_required(VERSION 2.8.3) cmake_minimum_required(VERSION 2.8.3)
project(hand_control) project(hand_control)
#set(CMAKE_CXX_FLAGS "-std=c++11 ${CMAKE_CXX_FLAGS}")
## Find catkin macros and libraries ## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages ## is used, also find other catkin packages
@ -116,6 +117,10 @@ add_dependencies(filtre ${catkin_EXPORTED_TARGETS})
add_executable(random_pcl_publisher src/random_pcl_publisher.cpp) add_executable(random_pcl_publisher src/random_pcl_publisher.cpp)
target_link_libraries(random_pcl_publisher ${catkin_LIBRARIES}) target_link_libraries(random_pcl_publisher ${catkin_LIBRARIES})
add_dependencies(random_pcl_publisher ${catkin_EXPORTED_TARGETS}) add_dependencies(random_pcl_publisher ${catkin_EXPORTED_TARGETS})
add_executable(pcl_displayer src/pcl_displayer.cpp)
target_link_libraries(pcl_displayer ${catkin_LIBRARIES})
add_dependencies(pcl_displayer ${catkin_EXPORTED_TARGETS})
## Add cmake target dependencies of the executable/library ## Add cmake target dependencies of the executable/library
## as an example, message headers may need to be generated before nodes ## as an example, message headers may need to be generated before nodes
# add_dependencies(hand_control_node hand_control_generate_messages_cpp) # add_dependencies(hand_control_node hand_control_generate_messages_cpp)

View file

@ -1,12 +1,12 @@
<launch> <launch>
<node name="filtre_z" pkg="hand_control" type="filtre"> <node name="filtre_z" pkg="hand_control" type="filtre">
<remap from="/filtre/input" to="random_pcl"/> <remap from="/filtre/input" to="/random_pcl"/>
</node> </node>
<param name="/filtre/zmax" value="100." type="double" /> <param name="/filtre/zmax" value="100." type="double" />
<node name="publisher" pkg="hand_control" type="random_pcl_publisher" > <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> </node>
<param name="/random/freq" value="1." type="double" /> <param name="/random/freq" value="1." type="double" />
<param name="/random/length" value="5" type="int" /> <param name="/random/length" value="5" type="int" />

View file

@ -25,17 +25,6 @@ class Callback {
// publication // publication
publisher.publish(pcl); publisher.publish(pcl);
ROS_INFO("PointCloud published"); ROS_INFO("PointCloud published");
ROS_INFO("filtered cloud :");
for(int i = 0; i < pcl->points.size(); ++i)
{
ROS_INFO("\nx : %f\ny : %f\nz : %f\nr : %d\ng : %d\nb : %d",
pcl->points[i].x,
pcl->points[i].y,
pcl->points[i].z,
pcl->points[i].r,
pcl->points[i].g,
pcl->points[i].b);
}
} }
Callback(ros::Publisher& pub) : publisher(pub), z_filtre() Callback(ros::Publisher& pub) : publisher(pub), z_filtre()

View file

@ -0,0 +1,48 @@
#include <ros/ros.h>
#include <pcl_ros/point_cloud.h>
#include <pcl/point_types.h>
#include <iostream>
#include <string>
#include <sstream>
typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloud;
class Callback {
public:
void
operator()(const PointCloud::ConstPtr& msg)
{
std::ostringstream stream;
stream << "PointCloud published :" << std::endl;
for(int i = 0; i < msg->points.size(); ++i)
{
pcl::PointXYZRGB p = msg->points[i];
stream << std::endl
<< "point # " << i << std::endl
<< "x : " << p.x << std::endl
<< "y : " << p.y << std::endl
<< "z : " << p.z << std::endl
<< "r : " << (int) p.r << std::endl
<< "g : " << (int) p.g << std::endl
<< "b : " << (int) p.b << std::endl;
}
ROS_INFO("%s", stream.str().c_str());
}
};
int
main(int argc, char** argv)
{
ros::init(argc, argv, "pcl_displayer");
ros::NodeHandle node("pcl_displayer");
// initialisation
ros::Subscriber subscriber = node.subscribe<PointCloud>("input", 1, Callback());
// démarrage
ROS_INFO("node started");
ros::spin();
ROS_INFO("exit");
return 0;
}

View file

@ -12,7 +12,8 @@ typedef pcl::common::UniformGenerator<float> UGenerator;
class Generator class Generator
{ {
public: public:
Generator(int len, double m, double M) : length(len), min(m), max(M), cgen() Generator(int len, double m, double M)
: length(len), min(m), max(M), cgen()
{ {
UGenerator::Parameters params(min, max, -1); UGenerator::Parameters params(min, max, -1);
cgen.setParameters(params); cgen.setParameters(params);
@ -23,16 +24,11 @@ class Generator
{ {
PointCloud::Ptr pcl(new PointCloud()); PointCloud::Ptr pcl(new PointCloud());
cgen.fill(length, length, *pcl); cgen.fill(length, length, *pcl);
ROS_INFO("random cloud :");
for (int i = 0; i < pcl->points.size(); ++i) for (int i = 0; i < pcl->points.size(); ++i)
{ {
ROS_INFO("\nx : %f\ny : %f\nz : %f\nr : %d\ng : %d\nb : %d", pcl->points[i].r = (uint8_t) 255;
pcl->points[i].x, pcl->points[i].g = (uint8_t) 255;
pcl->points[i].y, pcl->points[i].b = (uint8_t) 0;
pcl->points[i].z,
pcl->points[i].r,
pcl->points[i].g,
pcl->points[i].b);
} }
return pcl; return pcl;
} }