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