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 #include <Eigen/Geometry>
00039 #include <pcl/common/common.h>
00040 #include <pcl/console/parse.h>
00041 #include <pcl/console/time.h>
00042 #include <pcl/io/pcd_io.h>
00043 #include <cfloat>
00044 #include "pcl_visualization/point_cloud_handlers.h"
00045 #include "pcl_visualization/pcl_visualizer.h"
00046 #include "pcl_visualization/histogram_visualizer.h"
00047 #include <terminal_tools/print.h>
00048 #include <terminal_tools/parse.h>
00049 #include <terminal_tools/time.h>
00050
00051 using pcl::console::print_color;
00052 using pcl::console::print_error;
00053 using pcl::console::print_error;
00054 using pcl::console::print_warn;
00055 using pcl::console::print_info;
00056 using pcl::console::print_debug;
00057 using pcl::console::print_value;
00058 using pcl::console::print_highlight;
00059 using pcl::console::TT_BRIGHT;
00060 using pcl::console::TT_RED;
00061 using pcl::console::TT_GREEN;
00062 using pcl::console::TT_BLUE;
00063
00064 typedef pcl_visualization::PointCloudColorHandler<sensor_msgs::PointCloud2> ColorHandler;
00065 typedef ColorHandler::Ptr ColorHandlerPtr;
00066 typedef ColorHandler::ConstPtr ColorHandlerConstPtr;
00067
00068 typedef pcl_visualization::PointCloudGeometryHandler<sensor_msgs::PointCloud2> GeometryHandler;
00069 typedef GeometryHandler::Ptr GeometryHandlerPtr;
00070 typedef GeometryHandler::ConstPtr GeometryHandlerConstPtr;
00071
00072 #define NORMALS_SCALE 0.01
00073 #define PC_SCALE 0.001
00074
00075 bool
00076 isValidFieldName (const std::string &field)
00077 {
00078 if (field == "_")
00079 return (false);
00080
00081 if ((field == "vp_x") || (field == "vx") || (field == "vp_y") || (field == "vy") || (field == "vp_z") || (field == "vz"))
00082 return (false);
00083 return (true);
00084 }
00085
00086 bool
00087 isMultiDimensionalFeatureField (const sensor_msgs::PointField &field)
00088 {
00089 if (field.count > 1)
00090 return (true);
00091 return (false);
00092 }
00093
00094 void
00095 printHelp (int argc, char **argv)
00096 {
00097 print_error ("Syntax is: %s <file_name 1..N>.pcd <options>\n", argv[0]);
00098 print_info (" where options are:\n");
00099 print_info (" -bc r,g,b = background color\n");
00100 print_info (" -fc r,g,b = foreground color\n");
00101 print_info (" -ps X = point size ("); print_value ("1..64"); print_info (") \n");
00102 print_info (" -opaque X = rendered point cloud opacity ("); print_value ("0..1"); print_info (")\n");
00103
00104 print_info (" -ax "); print_value ("n"); print_info (" = enable on-screen display of ");
00105 print_color (stdout, TT_BRIGHT, TT_RED, "X"); print_color (stdout, TT_BRIGHT, TT_GREEN, "Y"); print_color (stdout, TT_BRIGHT, TT_BLUE, "Z");
00106 print_info (" axes and scale them to "); print_value ("n\n");
00107 print_info (" -ax_pos X,Y,Z = if axes are enabled, set their X,Y,Z position in space (default "); print_value ("0,0,0"); print_info (")\n");
00108
00109 print_info ("\n");
00110 print_info (" -cam (*) = use given camera settings as initial view\n");
00111 print_info (stderr, " (*) [Clipping Range / Focal Point / Position / ViewUp / Distance / Window Size / Window Pos] or use a <filename.cam> that contains the same information.\n");
00112
00113 print_info ("\n");
00114 print_info (" -multiview 0/1 = enable/disable auto-multi viewport rendering (default "); print_value ("disabled"); print_info (")\n");
00115 print_info ("\n");
00116
00117 print_info ("\n");
00118 print_info (" -normals 0/X = disable/enable the display of every Xth point's surface normal as lines (default "); print_value ("disabled"); print_info (")\n");
00119 print_info (" -normals_scale X = resize the normal unit vector size to X (default "); print_value ("0.02"); print_info (")\n");
00120 print_info ("\n");
00121 print_info (" -pc 0/X = disable/enable the display of every Xth point's principal curvatures as lines (default "); print_value ("disabled"); print_info (")\n");
00122 print_info (" -pc_scale X = resize the principal curvatures vectors size to X (default "); print_value ("0.02"); print_info (")\n");
00123 print_info ("\n");
00124
00125 print_info ("\n(Note: for multiple .pcd files, provide multiple -{fc,ps,opaque} parameters; they will be automatically assigned to the right file)\n");
00126 }
00127
00128
00129 int
00130 main (int argc, char** argv)
00131 {
00132 srand (time (0));
00133
00134 if (argc < 2)
00135 {
00136 printHelp (argc, argv);
00137 return (-1);
00138 }
00139
00140
00141 double bcolor[3] = {0, 0, 0};
00142 pcl::console::parse_3x_arguments (argc, argv, "-bc", bcolor[0], bcolor[1], bcolor[2]);
00143
00144 std::vector<double> fcolor_r, fcolor_b, fcolor_g;
00145 bool fcolorparam = pcl::console::parse_multiple_3x_arguments (argc, argv, "-fc", fcolor_r, fcolor_g, fcolor_b);
00146
00147 std::vector<int> psize;
00148 pcl::console::parse_multiple_arguments (argc, argv, "-ps", psize);
00149
00150 std::vector<double> opaque;
00151 pcl::console::parse_multiple_arguments (argc, argv, "-opaque", opaque);
00152
00153 int mview = 0;
00154 pcl::console::parse_argument (argc, argv, "-multiview", mview);
00155
00156 int normals = 0;
00157 pcl::console::parse_argument (argc, argv, "-normals", normals);
00158 double normals_scale = NORMALS_SCALE;
00159 pcl::console::parse_argument (argc, argv, "-normals_scale", normals_scale);
00160
00161 int pc = 0;
00162 pcl::console::parse_argument (argc, argv, "-pc", pc);
00163 double pc_scale = PC_SCALE;
00164 pcl::console::parse_argument (argc, argv, "-pc_scale", pc_scale);
00165
00166
00167 std::vector<int> p_file_indices;
00168 p_file_indices = pcl::console::parse_file_extension_argument (argc, argv, ".pcd");
00169 if (p_file_indices.size () == 0)
00170 {
00171 print_error ("No .PCD file given. Nothing to visualize.\n");
00172 return (-1);
00173 }
00174
00175
00176 int y_s = 0, x_s = 0;
00177 double x_step = 0, y_step = 0;
00178 if (mview)
00179 {
00180 print_highlight ("Multi-viewport rendering enabled.\n");
00181
00182 y_s = static_cast<int>(floor (sqrt (static_cast<float>(p_file_indices.size ()))));
00183 x_s = y_s + static_cast<int>(ceil ((p_file_indices.size () / static_cast<double>(y_s)) - y_s));
00184 x_step = static_cast<double>(1.0 / static_cast<double>(x_s));
00185 y_step = static_cast<double>(1.0 / static_cast<double>(y_s));
00186 print_highlight ("Preparing to load "); print_value ("%d", p_file_indices.size ());
00187 print_info (" files ("); print_value ("%d", x_s); print_info ("x"); print_value ("%d", y_s);
00188 print_info (" / "); print_value ("%f", x_step); print_info ("x"); print_value ("%f", y_step);
00189 print_info (")\n");
00190 }
00191
00192
00193 if (psize.size () != p_file_indices.size () && psize.size () > 0)
00194 for (size_t i = psize.size (); i < p_file_indices.size (); ++i)
00195 psize.push_back (1);
00196 if (opaque.size () != p_file_indices.size () && opaque.size () > 0)
00197 for (size_t i = opaque.size (); i < p_file_indices.size (); ++i)
00198 opaque.push_back (1.0);
00199
00200
00201 boost::shared_ptr<pcl_visualization::PCLHistogramVisualizer> ph;
00202 boost::shared_ptr<pcl_visualization::PCLVisualizer> p;
00203
00204
00205 float min_p = FLT_MAX; float max_p = -FLT_MAX;
00206
00207 int k = 0, l = 0, viewport = 0;
00208
00209 pcl::PCDReader pcd;
00210 pcl::console::TicToc tt;
00211 ColorHandlerPtr color_handler;
00212 GeometryHandlerPtr geometry_handler;
00213
00214 for (size_t i = 0; i < p_file_indices.size (); ++i)
00215 {
00216 sensor_msgs::PointCloud2 cloud;
00217 Eigen::Vector4f origin;
00218 Eigen::Quaternionf orientation;
00219 int version;
00220
00221 print_highlight (stderr, "Loading "); print_value (stderr, "%s ", argv[p_file_indices.at (i)]);
00222
00223 tt.tic ();
00224 if (pcd.read (argv[p_file_indices.at (i)], cloud, origin, orientation, version) < 0)
00225 return (-1);
00226
00227 std::stringstream cloud_name;
00228
00229
00230 if (cloud.fields.size () == 1 && isMultiDimensionalFeatureField (cloud.fields[0]))
00231 {
00232 cloud_name << argv[p_file_indices.at (i)];
00233
00234 if (!ph)
00235 ph.reset (new pcl_visualization::PCLHistogramVisualizer ());
00236 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" seconds : "); print_value ("%d", cloud.fields[0].count); print_info (" points]\n");
00237
00238 pcl::getMinMax (cloud, 0, cloud.fields[0].name, min_p, max_p);
00239 ph->addFeatureHistogram (cloud, cloud.fields[0].name, cloud_name.str ());
00240 continue;
00241 }
00242
00243 cloud_name << argv[p_file_indices.at (i)] << "-" << i;
00244
00245 if (!p)
00246 p.reset (new pcl_visualization::PCLVisualizer (argc, argv, "PCD viewer"));
00247
00248
00249 if (mview)
00250 {
00251 p->createViewPort (k * x_step, l * y_step, (k + 1) * x_step, (l + 1) * y_step, viewport);
00252 k++;
00253 if (k >= x_s)
00254 {
00255 k = 0;
00256 l++;
00257 }
00258 }
00259
00260
00261 pcl::PointCloud<pcl::PointXYZ> cloud_xyz;
00262 pcl::fromROSMsg (cloud, cloud_xyz);
00263
00264 if (cloud_xyz.points.size () == 0)
00265 {
00266 print_error ("[error: no points found!]\n");
00267 return (-1);
00268 }
00269 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" seconds : "); print_value ("%d", (int)cloud_xyz.points.size ()); print_info (" points]\n");
00270 print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (cloud).c_str ());
00271
00272
00273 if (fcolorparam)
00274 {
00275 if (fcolor_r.size () > i && fcolor_g.size () > i && fcolor_b.size () > i)
00276 color_handler.reset (new pcl_visualization::PointCloudColorHandlerCustom<sensor_msgs::PointCloud2> (cloud, fcolor_r[i], fcolor_g[i], fcolor_b[i]));
00277 else
00278 color_handler.reset (new pcl_visualization::PointCloudColorHandlerRandom<sensor_msgs::PointCloud2> (cloud));
00279 }
00280 else
00281 color_handler.reset (new pcl_visualization::PointCloudColorHandlerRandom<sensor_msgs::PointCloud2> (cloud));
00282
00283
00284 geometry_handler.reset (new pcl_visualization::PointCloudGeometryHandlerXYZ<sensor_msgs::PointCloud2> (cloud));
00285
00286 p->addPointCloud (cloud_xyz, geometry_handler, color_handler, cloud_name.str (), viewport);
00287
00288
00289 if (normals != 0)
00290 {
00291 int normal_idx = pcl::getFieldIndex (cloud, "normal_x");
00292 if (normal_idx == -1)
00293 {
00294 print_error ("Normal information requested but not available.\n");
00295 continue;
00296
00297 }
00298
00299
00300 pcl::PointCloud<pcl::Normal> cloud_normals;
00301 pcl::fromROSMsg (cloud, cloud_normals);
00302 std::stringstream cloud_name_normals;
00303 cloud_name_normals << argv[p_file_indices.at (i)] << "-" << i << "-normals";
00304 p->addPointCloudNormals (cloud_xyz, cloud_normals, normals, normals_scale, cloud_name_normals.str (), viewport);
00305 }
00306
00307
00308 if (pc != 0)
00309 {
00310 if (normals == 0)
00311 normals = pc;
00312
00313 int normal_idx = pcl::getFieldIndex (cloud, "normal_x");
00314 if (normal_idx == -1)
00315 {
00316 print_error ("Normal information requested but not available.\n");
00317 continue;
00318
00319 }
00320 int pc_idx = pcl::getFieldIndex (cloud, "principal_curvature_x");
00321 if (pc_idx == -1)
00322 {
00323 print_error ("Principal Curvature information requested but not available.\n");
00324 continue;
00325
00326 }
00327
00328
00329 pcl::PointCloud<pcl::Normal> cloud_normals;
00330 pcl::fromROSMsg (cloud, cloud_normals);
00331 pcl::PointCloud<pcl::PrincipalCurvatures> cloud_pc;
00332 pcl::fromROSMsg (cloud, cloud_pc);
00333 std::stringstream cloud_name_normals_pc;
00334 cloud_name_normals_pc << argv[p_file_indices.at (i)] << "-" << i << "-normals";
00335 int factor = std::min (normals, pc);
00336 p->addPointCloudNormals (cloud_xyz, cloud_normals, factor, normals_scale, cloud_name_normals_pc.str (), viewport);
00337 p->setPointCloudRenderingProperties (pcl_visualization::PCL_VISUALIZER_COLOR, 1.0, 0.0, 0.0, cloud_name_normals_pc.str ());
00338 p->setPointCloudRenderingProperties (pcl_visualization::PCL_VISUALIZER_LINE_WIDTH, 3, cloud_name_normals_pc.str ());
00339 cloud_name_normals_pc << "-pc";
00340 p->addPointCloudPrincipalCurvatures (cloud_xyz, cloud_normals, cloud_pc, factor, pc_scale, cloud_name_normals_pc.str (), viewport);
00341 p->setPointCloudRenderingProperties (pcl_visualization::PCL_VISUALIZER_LINE_WIDTH, 3, cloud_name_normals_pc.str ());
00342 }
00343
00344
00345 if (!fcolorparam)
00346 {
00347 for (size_t f = 0; f < cloud.fields.size (); ++f)
00348 {
00349 if (cloud.fields[f].name == "rgb" || cloud.fields[f].name == "rgba")
00350 color_handler.reset (new pcl_visualization::PointCloudColorHandlerRGBField<sensor_msgs::PointCloud2> (cloud));
00351 else
00352 {
00353 if (!isValidFieldName (cloud.fields[f].name))
00354 continue;
00355 color_handler.reset (new pcl_visualization::PointCloudColorHandlerGenericField<sensor_msgs::PointCloud2> (cloud, cloud.fields[f].name));
00356 }
00357
00358 p->addPointCloud (cloud_xyz, color_handler, cloud_name.str (), viewport);
00359 }
00360 }
00361
00362 geometry_handler.reset (new pcl_visualization::PointCloudGeometryHandlerSurfaceNormal<sensor_msgs::PointCloud2> (cloud));
00363 if (geometry_handler->isCapable ())
00364 p->addPointCloud (cloud_xyz, geometry_handler, cloud_name.str (), viewport);
00365
00366
00367 if (psize.size () > 0)
00368 p->setPointCloudRenderingProperties (pcl_visualization::PCL_VISUALIZER_POINT_SIZE, psize.at (i), cloud_name.str ());
00369
00370
00371 if (opaque.size () > 0)
00372 p->setPointCloudRenderingProperties (pcl_visualization::PCL_VISUALIZER_OPACITY, opaque.at (i), cloud_name.str ());
00373 }
00374
00375 if (p)
00376 p->setBackgroundColor (bcolor[0], bcolor[1], bcolor[2]);
00377
00378 double axes = 0.0;
00379 pcl::console::parse_argument (argc, argv, "-ax", axes);
00380 if (axes != 0.0 && p)
00381 {
00382 double ax_x = 0.0, ax_y = 0.0, ax_z = 0.0;
00383 pcl::console::parse_3x_arguments (argc, argv, "-ax_pos", ax_x, ax_y, ax_z, false);
00384
00385 p->addCoordinateSystem (axes, ax_x, ax_y, ax_z);
00386 }
00387
00388 if (p)
00389 p->spin ();
00390 if (ph)
00391 {
00392 print_highlight ("Setting the global Y range for all histograms to: "); print_value ("%f -> %f\n", min_p, max_p);
00393 ph->setGlobalYRange (min_p, max_p);
00394 ph->updateWindowPositions ();
00395 ph->spin ();
00396 }
00397 }
00398