Go to the documentation of this file.00001
00002 #include <pcl/point_cloud.h>
00003 #include <pcl/point_types.h>
00004 #include <pcl/io/pcd_io.h>
00005 #include <pcl/console/print.h>
00006 #include <pcl/console/parse.h>
00007 #include <pcl/console/time.h>
00008
00009 #include <pcl/recognition/linemod/line_rgbd.h>
00010 #include <pcl/recognition/color_gradient_modality.h>
00011 #include <pcl/recognition/surface_normal_modality.h>
00012
00013
00014 using namespace pcl;
00015 using namespace pcl::io;
00016 using namespace pcl::console;
00017
00018 typedef pcl::PointCloud<pcl::PointXYZRGBA> PointCloudXYZRGBA;
00019
00020 void
00021 printHelp (int, char **argv)
00022 {
00023 print_error ("Syntax is: %s input.pcd min_depth max_depth max_height output_template.lmt\n", argv[0]);
00024 print_info (" where options are:\n");
00025 }
00026
00027 void printElapsedTimeAndNumberOfPoints (double t, int w, int h=1)
00028 {
00029 print_info ("[done, "); print_value ("%g", t); print_info (" ms : ");
00030 print_value ("%d", w*h); print_info (" points]\n");
00031 }
00032
00033 bool
00034 loadCloud (const std::string & filename, PointCloudXYZRGBA & cloud)
00035 {
00036 TicToc tt;
00037 print_highlight ("Loading "); print_value ("%s ", filename.c_str ());
00038
00039 tt.tic ();
00040 if (loadPCDFile (filename, cloud) < 0)
00041 return (false);
00042
00043 printElapsedTimeAndNumberOfPoints (tt.toc (), cloud.width, cloud.height);
00044
00045 print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (cloud).c_str ());
00046
00047 return (true);
00048 }
00049
00050
00051
00052
00053 int
00054 main (int argc, char** argv)
00055 {
00056 print_info ("Train one or more linemod templates. For more information, use: %s -h\n", argv[0]);
00057
00058
00059 if (argc == 1)
00060 {
00061 printHelp (argc, argv);
00062 return (-1);
00063 }
00064
00065
00066 float grad_mag_thresh = 10.0f;
00067 parse_argument (argc, argv, "-grad_mag_thresh", grad_mag_thresh);
00068
00069
00070 float detect_thresh = 0.75f;
00071 parse_argument (argc, argv, "-detect_thresh", detect_thresh);
00072
00073
00074 std::vector<int> lmt_file_indices;
00075 lmt_file_indices = parse_file_extension_argument (argc, argv, ".lmt");
00076 if (lmt_file_indices.empty ())
00077 {
00078 print_error ("Need at least one input LMT file.\n");
00079 return (-1);
00080 }
00081
00082 LineRGBD<PointXYZRGBA> line_rgbd;
00083 line_rgbd.setGradientMagnitudeThreshold (grad_mag_thresh);
00084 line_rgbd.setDetectionThreshold (detect_thresh);
00085
00086
00087 for (size_t i = 0; i < lmt_file_indices.size (); ++i)
00088 {
00089
00090 std::string lmt_filename = argv[lmt_file_indices[i]];
00091 line_rgbd.loadTemplates (lmt_filename);
00092 }
00093
00094
00095 std::string input_filename;
00096 if (parse_argument (argc, argv, "-input", input_filename) < 0)
00097 return (-1);
00098 PointCloudXYZRGBA::Ptr cloud (new PointCloudXYZRGBA);
00099 if (!loadCloud (input_filename, *cloud))
00100 return (-1);
00101
00102
00103 line_rgbd.setInputCloud (cloud);
00104 line_rgbd.setInputColors (cloud);
00105
00106 std::vector<LineRGBD<PointXYZRGBA>::Detection> detections;
00107 line_rgbd.detect (detections);
00108
00109 for (size_t i = 0; i < detections.size (); ++i)
00110 {
00111 const LineRGBD<PointXYZRGBA>::Detection & d = detections[i];
00112 const BoundingBoxXYZ & bb = d.bounding_box;
00113 print_info ("%zu %zu %f (%f %f %f) (%f %f %f)\n",
00114 d.detection_id, d.template_id, d.response,
00115 bb.x, bb.y, bb.z, bb.width, bb.height, bb.depth);
00116 }
00117 }