# -*- coding: utf-8 -*- # How to visualize a range image # http://pointclouds.org/documentation/tutorials/range_image_visualization.php#range-image-visualization #include #include #include #include #include #include #include #include typedef pcl::PointXYZ PointType; // -----Parameters----- float angular_resolution_x = 0.5f, angular_resolution_y = angular_resolution_x; pcl::RangeImage::CoordinateFrame coordinate_frame = pcl::RangeImage::CAMERA_FRAME; bool live_update = false; // -----Help----- void printUsage (const char* progName) { std::cout << "\n\nUsage: "<\n\n" << "Options:\n" << "-------------------------------------------\n" << "-rx angular resolution in degrees (default "< angular resolution in degrees (default "< coordinate frame (default "<< (int)coordinate_frame<<")\n" << "-l live update - update the range image according to the selected view in the 3D viewer.\n" << "-h this help\n" << "\n\n"; } void setViewerPose (pcl::visualization::PCLVisualizer& viewer, const Eigen::Affine3f& viewer_pose) { Eigen::Vector3f pos_vector = viewer_pose * Eigen::Vector3f(0, 0, 0); Eigen::Vector3f look_at_vector = viewer_pose.rotation () * Eigen::Vector3f(0, 0, 1) + pos_vector; Eigen::Vector3f up_vector = viewer_pose.rotation () * Eigen::Vector3f(0, -1, 0); viewer.setCameraPosition (pos_vector[0], pos_vector[1], pos_vector[2], look_at_vector[0], look_at_vector[1], look_at_vector[2], up_vector[0], up_vector[1], up_vector[2]); } // -------------- // -----Main----- // -------------- int main (int argc, char** argv) { // -------------------------------------- // -----Parse Command Line Arguments----- // -------------------------------------- if (pcl::console::find_argument (argc, argv, "-h") >= 0) { printUsage (argv[0]); return 0; } if (pcl::console::find_argument (argc, argv, "-l") >= 0) { live_update = true; std::cout << "Live update is on.\n"; } if (pcl::console::parse (argc, argv, "-rx", angular_resolution_x) >= 0) std::cout << "Setting angular resolution in x-direction to "<= 0) std::cout << "Setting angular resolution in y-direction to "<= 0) { coordinate_frame = pcl::RangeImage::CoordinateFrame (tmp_coordinate_frame); std::cout << "Using coordinate frame "<< (int)coordinate_frame<<".\n"; } angular_resolution_x = pcl::deg2rad (angular_resolution_x); angular_resolution_y = pcl::deg2rad (angular_resolution_y); // ------------------------------------------------------------------ // -----Read pcd file or create example point cloud if not given----- // ------------------------------------------------------------------ pcl::PointCloud::Ptr point_cloud_ptr (new pcl::PointCloud); pcl::PointCloud& point_cloud = *point_cloud_ptr; Eigen::Affine3f scene_sensor_pose (Eigen::Affine3f::Identity ()); std::vector pcd_filename_indices = pcl::console::parse_file_extension_argument (argc, argv, "pcd"); if (!pcd_filename_indices.empty ()) { std::string filename = argv[pcd_filename_indices[0]]; if (pcl::io::loadPCDFile (filename, point_cloud) == -1) { std::cout << "Was not able to open file \""< Genarating example point cloud.\n\n"; for (float x=-0.5f; x<=0.5f; x+=0.01f) { for (float y=-0.5f; y<=0.5f; y+=0.01f) { PointType point; point.x = x; point.y = y; point.z = 2.0f - y; point_cloud.points.push_back (point); } } point_cloud.width = (int) point_cloud.points.size (); point_cloud.height = 1; } // ----------------------------------------------- // -----Create RangeImage from the PointCloud----- // ----------------------------------------------- float noise_level = 0.0; float min_range = 0.0f; int border_size = 1; boost::shared_ptr range_image_ptr(new pcl::RangeImage); pcl::RangeImage& range_image = *range_image_ptr; range_image.createFromPointCloud (point_cloud, angular_resolution_x, angular_resolution_y, pcl::deg2rad (360.0f), pcl::deg2rad (180.0f), scene_sensor_pose, coordinate_frame, noise_level, min_range, border_size); // -------------------------------------------- // -----Open 3D viewer and add point cloud----- // -------------------------------------------- pcl::visualization::PCLVisualizer viewer ("3D Viewer"); viewer.setBackgroundColor (1, 1, 1); pcl::visualization::PointCloudColorHandlerCustom range_image_color_handler (range_image_ptr, 0, 0, 0); viewer.addPointCloud (range_image_ptr, range_image_color_handler, "range image"); viewer.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "range image"); //viewer.addCoordinateSystem (1.0f, "global"); //PointCloudColorHandlerCustom point_cloud_color_handler (point_cloud_ptr, 150, 150, 150); //viewer.addPointCloud (point_cloud_ptr, point_cloud_color_handler, "original point cloud"); viewer.initCameraParameters (); setViewerPose(viewer, range_image.getTransformationToWorldSystem ()); // -------------------------- // -----Show range image----- // -------------------------- pcl::visualization::RangeImageVisualizer range_image_widget ("Range image"); range_image_widget.showRangeImage (range_image); //-------------------- // -----Main loop----- //-------------------- while (!viewer.wasStopped ()) { range_image_widget.spinOnce (); viewer.spinOnce (); pcl_sleep (0.01); if (live_update) { scene_sensor_pose = viewer.getViewerPose(); range_image.createFromPointCloud (point_cloud, angular_resolution_x, angular_resolution_y, pcl::deg2rad (360.0f), pcl::deg2rad (180.0f), scene_sensor_pose, pcl::RangeImage::LASER_FRAME, noise_level, min_range, border_size); range_image_widget.showRangeImage (range_image); } } }