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