pcl_plotter.hpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2011, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  */
00037 
00038 #ifndef PCL_VISUALUALIZATION_PCL_PLOTTER_IMPL_H_
00039 #define PCL_VISUALUALIZATION_PCL_PLOTTER_IMPL_H_
00040 
00041 template <typename PointT> bool
00042 pcl::visualization::PCLPlotter::addFeatureHistogram (
00043     const pcl::PointCloud<PointT> &cloud, int hsize, 
00044     const std::string &id, int win_width, int win_height)
00045 {
00046   std::vector<double> array_x(hsize), array_y(hsize);
00047   
00048   // Parse the cloud data and store it in the array
00049   for (int i = 0; i < hsize; ++i)
00050   {
00051     array_x[i] = i;
00052     array_y[i] = cloud.points[0].histogram[i];
00053   }
00054   
00055   this->addPlotData(array_x, array_y, id.c_str(), vtkChart::LINE);
00056   setWindowSize (win_width, win_height);
00057   return true;
00058 }
00059 
00060 
00061 template <typename PointT> bool
00062 pcl::visualization::PCLPlotter::addFeatureHistogram (
00063     const pcl::PointCloud<PointT> &cloud, 
00064     const std::string &field_name,
00065     const int index, 
00066     const std::string &id, int win_width, int win_height)
00067 {
00068   if (index < 0 || index >= cloud.points.size ())
00069   {
00070     PCL_ERROR ("[addFeatureHistogram] Invalid point index (%d) given!\n", index);
00071     return (false);
00072   }
00073 
00074   // Get the fields present in this cloud
00075   std::vector<pcl::PCLPointField> fields;
00076   // Check if our field exists
00077   int field_idx = pcl::getFieldIndex<PointT> (cloud, field_name, fields);
00078   if (field_idx == -1)
00079   {
00080     PCL_ERROR ("[addFeatureHistogram] The specified field <%s> does not exist!\n", field_name.c_str ());
00081     return (false);
00082   }
00083 
00084   int hsize = fields[field_idx].count;
00085   std::vector<double> array_x (hsize), array_y (hsize);
00086   
00087   for (int i = 0; i < hsize; ++i)
00088   {
00089     array_x[i] = i;
00090     float data;
00091     // TODO: replace float with the real data type
00092     memcpy (&data, reinterpret_cast<const char*> (&cloud.points[index]) + fields[field_idx].offset + i * sizeof (float), sizeof (float));
00093     array_y[i] = data;
00094   }
00095   
00096   this->addPlotData(array_x, array_y, id.c_str(), vtkChart::LINE);
00097   setWindowSize (win_width, win_height);
00098   return (true);
00099 }
00100 
00101 #endif  /* PCL_VISUALUALIZATION_PCL_PLOTTER_IMPL_H_ */
00102 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:28:09