From e939b43ad745abd40a84c1cd09d0788d1be11510 Mon Sep 17 00:00:00 2001 From: SunBlack Date: Fri, 25 Nov 2022 13:12:18 +0100 Subject: [PATCH] Drop most CUDA apps, as they are never built. --- cuda/apps/src/kinect_cloud.cpp | 129 ----- cuda/apps/src/kinect_debayering.cpp | 106 ----- cuda/apps/src/kinect_dediscretize.cpp | 110 ----- cuda/apps/src/kinect_mapping.cpp | 291 ------------ cuda/apps/src/kinect_normals_cuda.cpp | 263 ----------- cuda/apps/src/kinect_planes_cuda.cpp | 320 ------------- cuda/apps/src/kinect_ransac.cpp | 232 --------- cuda/apps/src/kinect_segmentation_cuda.cpp | 442 ------------------ .../src/kinect_segmentation_planes_cuda.cpp | 311 ------------ cuda/apps/src/kinect_tool_standalone.cpp | 117 ----- 10 files changed, 2321 deletions(-) delete mode 100644 cuda/apps/src/kinect_cloud.cpp delete mode 100644 cuda/apps/src/kinect_debayering.cpp delete mode 100644 cuda/apps/src/kinect_dediscretize.cpp delete mode 100644 cuda/apps/src/kinect_mapping.cpp delete mode 100644 cuda/apps/src/kinect_normals_cuda.cpp delete mode 100644 cuda/apps/src/kinect_planes_cuda.cpp delete mode 100644 cuda/apps/src/kinect_ransac.cpp delete mode 100644 cuda/apps/src/kinect_segmentation_cuda.cpp delete mode 100644 cuda/apps/src/kinect_segmentation_planes_cuda.cpp delete mode 100644 cuda/apps/src/kinect_tool_standalone.cpp diff --git a/cuda/apps/src/kinect_cloud.cpp b/cuda/apps/src/kinect_cloud.cpp deleted file mode 100644 index 4390c46828b..00000000000 --- a/cuda/apps/src/kinect_cloud.cpp +++ /dev/null @@ -1,129 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2010, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id$ - * - */ - -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include - -#include - -using namespace message_filters; -using namespace pcl; -using namespace pcl_cuda; - -DisparityToCloud d2c; -ros::Publisher pub; - -struct EventHelper -{ - void - callback (const pcl::PCLImage::ConstPtr &depth, - const pcl::PCLImage::ConstPtr &rgb, - const pcl::CameraInfo::ConstPtr &info) - { - //using Indices = pcl_cuda::SampleConsensusModel::Indices; - - //pcl_cuda::PointCloudAOS::Ptr data (new pcl_cuda::PointCloudAOS); - PointCloudAOS::Ptr data; - d2c.callback (depth, rgb, info, data); - - SampleConsensusModelPlane::Ptr sac_model (new SampleConsensusModelPlane (data)); -// SampleConsensusModelPlane::Ptr sac_model (new pcl_cuda::SampleConsensusModelPlane (data)); - RandomSampleConsensus sac (sac_model); - sac.setDistanceThreshold (0.05); - - if (!sac.computeModel (2)) - std::cerr << "Failed to compute model" << std::endl; - - // Convert data from Thrust/HOST to PCL - pcl::PointCloud output; -// pcl_cuda::toPCL (*data, output); - - output.header.stamp = ros::Time::now (); - pub.publish (output); - } -}; - -int -main (int argc, char **argv) -{ - ros::init (argc, argv, "disparity_to_cloud"); - ros::NodeHandle nh; - - // Prepare output - pub = nh.advertise("output", 1); - - // Subscribe to topics - Synchronizer > sync_rgb (30); - Synchronizer > sync (30); - Subscriber sub_depth, sub_rgb; - Subscriber sub_info; - sub_depth.subscribe (nh, "/camera/depth/image", 30); - sub_rgb.subscribe (nh, "/camera/rgb/image_color", 30); - sub_info.subscribe (nh, "/camera/rgb/camera_info", 120); - //sub_info.subscribe (nh, "/camera/depth/camera_info", 120); - - EventHelper h; - - if (argc > 1 && atoi (argv[1]) == 1) - { - ROS_INFO ("[disparity_to_cloud] Using RGB to color the points."); - sync_rgb.connectInput (sub_depth, sub_rgb, sub_info); - //sync_rgb.registerCallback (bind (&pcl_cuda::DisparityToCloud::callback, k, _1, _2, _3)); - sync_rgb.registerCallback (std::bind (&EventHelper::callback, &h, _1, _2, _3)); - } - else - { - sync.connectInput (sub_depth, sub_info); - //sync.registerCallback (bind (&pcl_cuda::DisparityToCloud::callback, k, _1, PCLImageConstPtr (), _2)); - sync.registerCallback (std::bind (&EventHelper::callback, &h, _1, PCLImageConstPtr (), _2)); - } - - // Do this indefinitely - ros::spin (); - - return (0); -} diff --git a/cuda/apps/src/kinect_debayering.cpp b/cuda/apps/src/kinect_debayering.cpp deleted file mode 100644 index 1b9f075ad5a..00000000000 --- a/cuda/apps/src/kinect_debayering.cpp +++ /dev/null @@ -1,106 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2010, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id$ - * - */ - -#include -#include -#include -#include -#include - -#include - -#include -#include -#include - - -class SimpleKinectTool -{ - public: - //SimpleKinectTool () : viewer ("KinectGrabber"), init_(false) {} - - void cloud_cb_ (const openni_wrapper::Image::Ptr& image) - { - thrust::host_vector rgb_image(image->getWidth () * image->getHeight ()); - cv::Mat cv_image( image->getHeight (), image->getWidth (), CV_8UC3 ); - { - pcl::ScopeTime t ("computeBilinear+memcpy"); - debayering.computeBilinear (image, rgb_image); - //debayering.computeEdgeAware (image, rgb_image); - // now fill image and show! - pcl::ScopeTime t2 ("memcpy"); - memcpy (cv_image.data, &rgb_image[0], image->getWidth () * image->getHeight () * 3); - } - imshow ("test", cv_image); - } - - void run (const std::string& device_id) - { - cv::namedWindow("test", CV_WINDOW_AUTOSIZE); - pcl::Grabber* interface = new pcl::OpenNIGrabber(device_id); - - std::function f = std::bind (&SimpleKinectTool::cloud_cb_, this, _1); - - interface->registerCallback (f); - - interface->start (); - - while (true) - { - //sleep (1); - cv::waitKey(10); - } - - interface->stop (); - } - - pcl_cuda::Debayering debayering; - std::mutex mutex_; - bool init_; -}; - -int main (int argc, char** argv) -{ - std::string device_id = "#1"; - if (argc == 2) - { - device_id = argv[1]; - } - SimpleKinectTool v; - v.run (device_id); - return 0; -} diff --git a/cuda/apps/src/kinect_dediscretize.cpp b/cuda/apps/src/kinect_dediscretize.cpp deleted file mode 100644 index 18840374bbf..00000000000 --- a/cuda/apps/src/kinect_dediscretize.cpp +++ /dev/null @@ -1,110 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2010, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id$ - * - */ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include - - -class SimpleKinectTool -{ - public: - SimpleKinectTool () : viewer ("KinectGrabber"), init_(false) {} - - void cloud_cb_ (const openni_wrapper::Image::Ptr& image, const openni_wrapper::DepthImage::Ptr& depth_image, float constant) - { - pcl_cuda::PointCloudAOS::Ptr data; - { - pcl::ScopeTime t ("time:"); - d2c.compute (depth_image, image, constant, data); - } - //d2c.callback (depth_image, constant, *data); - - pcl::PointCloud::Ptr output (new pcl::PointCloud); - pcl_cuda::toPCL (*data, *output); - - viewer.showCloud (output); - - } - - void run (const std::string& device_id) - { - pcl::Grabber* interface = new pcl::OpenNIGrabber(device_id); - - std::function f = std::bind (&SimpleKinectTool::cloud_cb_, this, _1, _2, _3); - - interface->registerCallback (f); - - //viewer.runOnVisualizationThread (fn, "viz_cb"); - interface->start (); - - while (true) - { - sleep (1); - } - - interface->stop (); - } - - pcl_cuda::DisparityToCloud d2c; - pcl::visualization::CloudViewer viewer; - std::mutex mutex_; - bool init_; -}; - -int main (int argc, char** argv) -{ - std::string device_id = "#1"; - if (argc == 2) - { - device_id = argv[1]; - } - SimpleKinectTool v; - v.run (device_id); - return 0; -} diff --git a/cuda/apps/src/kinect_mapping.cpp b/cuda/apps/src/kinect_mapping.cpp deleted file mode 100644 index 834fdf1be87..00000000000 --- a/cuda/apps/src/kinect_mapping.cpp +++ /dev/null @@ -1,291 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2010, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id$ - * - */ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -#include -#include - -#include -#include - -#include -#include -#include - - -using namespace pcl_cuda; - -template