00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #include <signal.h>
00040 #include <ros/ros.h>
00041 #include <std_msgs/String.h>
00042 #include <boost/thread/mutex.hpp>
00043 #include <boost/thread.hpp>
00044
00045 #include <pcl/point_types.h>
00046 #include <pcl_ros/point_cloud.h>
00047 #include <pcl/visualization/pcl_visualizer.h>
00048 #include <pcl/features/feature.h>
00049 #include <pcl/common/centroid.h>
00050
00051 using pcl::visualization::PointCloudColorHandlerGenericField;
00052
00053 typedef pcl::PointXYZ Point;
00054 typedef pcl::PointCloud<Point> PointCloud;
00055 typedef pcl::PointXYZRGB PointRGB;
00056 typedef pcl::PointCloud<PointRGB> PointCloudRGB;
00057
00058
00059 sensor_msgs::PointCloud2ConstPtr cloud_, cloud_old_;
00060 boost::mutex m;
00061 bool viewer_initialized_;
00062 int counter_;
00063
00064 void cloud_cb(const sensor_msgs::PointCloud2ConstPtr& cloud)
00065 {
00066 m.lock ();
00067 printf("\rPointCloud with %d data points (%s), stamp %f, and frame %s.",
00068 cloud->width * cloud->height, pcl::getFieldsList(*cloud).c_str(),
00069 cloud->header.stamp.toSec(), cloud->header.frame_id.c_str());
00070 cloud_ = cloud;
00071 m.unlock();
00072 }
00073
00074 void updateVisualization()
00075 {
00076 PointCloud cloud_xyz;
00077 PointCloudRGB cloud_xyz_rgb;
00078 EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
00079 Eigen::Vector4f xyz_centroid;
00080
00081 ros::WallDuration d(0.01);
00082 bool rgb = false;
00083 std::vector<sensor_msgs::PointField> fields;
00084
00085
00086 pcl::visualization::PCLVisualizer viewer("Point Cloud Viewer");
00087
00088
00089 viewer.addCoordinateSystem(0.1);
00090
00091 while(true)
00092 {
00093 d.sleep();
00094
00095
00096 if(!cloud_ || cloud_->width<=0)
00097 continue;
00098
00099 viewer.spinOnce(1);
00100
00101 if(cloud_old_ == cloud_)
00102 continue;
00103 m.lock ();
00104
00105
00106 if(pcl::getFieldIndex(*cloud_, "rgb") != -1)
00107 {
00108 rgb = true;
00109 pcl::fromROSMsg(*cloud_, cloud_xyz_rgb);
00110 }
00111 else
00112 {
00113 rgb = false;
00114 pcl::fromROSMsg(*cloud_, cloud_xyz);
00115 pcl::getFields(cloud_xyz, fields);
00116 }
00117 cloud_old_ = cloud_;
00118 m.unlock();
00119
00120
00121 viewer.removePointCloud("cloud");
00122
00123
00124 if(rgb && pcl::getFieldIndex(cloud_xyz_rgb, "rgb", fields) != -1 &&
00125 cloud_xyz_rgb.points[0].rgb != 0)
00126 {
00127
00128 if(!viewer_initialized_)
00129 {
00130 computeMeanAndCovarianceMatrix(cloud_xyz_rgb, covariance_matrix, xyz_centroid);
00131 viewer.initCameraParameters();
00132 viewer.setCameraPosition(xyz_centroid(0), xyz_centroid(1), xyz_centroid(2)+3.0, 0, -1, 0);
00133 ROS_INFO_STREAM("[PointCloudViewer:] Point cloud viewer camera initialized in: [" <<
00134 xyz_centroid(0) << ", " << xyz_centroid(1) << ", " << xyz_centroid(2)+3.0 << "]");
00135 viewer_initialized_ = true;
00136 }
00137
00138
00139 pcl::visualization::PointCloudColorHandlerRGBField<PointRGB> color_handler(
00140 cloud_xyz_rgb.makeShared());
00141 viewer.addPointCloud(cloud_xyz_rgb.makeShared(), color_handler, "cloud");
00142 }
00143 else
00144 {
00145
00146 if(!viewer_initialized_)
00147 {
00148 computeMeanAndCovarianceMatrix(cloud_xyz_rgb, covariance_matrix, xyz_centroid);
00149 viewer.initCameraParameters();
00150 viewer.setCameraPosition(xyz_centroid(0), xyz_centroid(1), xyz_centroid(2)+3.0, 0, -1, 0);
00151 ROS_INFO_STREAM("[PointCloudViewer:] Point cloud viewer camera initialized in: [" <<
00152 xyz_centroid(0) << ", " << xyz_centroid(1) << ", " << xyz_centroid(2)+3.0 << "]");
00153 viewer_initialized_ = true;
00154 }
00155
00156
00157 if(pcl::getFieldIndex(cloud_xyz_rgb, "rgb", fields) != -1)
00158 {
00159 if(cloud_xyz_rgb.points[0].rgb == 0)
00160 {
00161 pcl::copyPointCloud(cloud_xyz_rgb, cloud_xyz);
00162 }
00163 }
00164
00165
00166 PointCloudColorHandlerGenericField<Point> color_handler (cloud_xyz.makeShared(), "z");
00167 if (!color_handler.isCapable ())
00168 {
00169 ROS_WARN_STREAM("[PointCloudViewer:] Cannot create curvature color handler!");
00170 pcl::visualization::PointCloudColorHandlerCustom<Point> color_handler(
00171 cloud_xyz.makeShared(), 255, 0, 255);
00172 }
00173
00174 viewer.addPointCloud(cloud_xyz.makeShared(), color_handler, "cloud");
00175 }
00176
00177 counter_++;
00178 }
00179 }
00180
00181 void sigIntHandler(int sig)
00182 {
00183 exit(0);
00184 }
00185
00186
00187 int main(int argc, char** argv)
00188 {
00189 ros::init(argc, argv, "pointcloud_viewer", ros::init_options::NoSigintHandler);
00190 ros::NodeHandle nh;
00191 viewer_initialized_ = false;
00192 counter_ = 0;
00193
00194
00195 ros::Subscriber sub = nh.subscribe("input", 30, cloud_cb);
00196
00197 ROS_INFO("Subscribing to %s for PointCloud2 messages...", nh.resolveName ("input").c_str ());
00198
00199 signal(SIGINT, sigIntHandler);
00200
00201 boost::thread visualization_thread(&updateVisualization);
00202
00203
00204 ros::spin();
00205
00206
00207 visualization_thread.join();
00208 return (0);
00209 }
00210