image_viewer.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) 2009-2012, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  */
00038 
00039 #ifndef PCL_VISUALIZATION_IMAGE_VISUALIZER_HPP_
00040 #define PCL_VISUALIZATION_IMAGE_VISUALIZER_HPP_
00041 
00042 #include <vtkContextActor.h>
00043 #include <vtkContextScene.h>
00044 #include <vtkImageData.h>
00045 #include <vtkImageFlip.h>
00046 #include <vtkPointData.h>
00047 #include <vtkImageViewer.h>
00048 
00049 #include <pcl/visualization/common/common.h>
00050 #include <pcl/search/organized.h>
00051 
00053 template <typename T> void
00054 pcl::visualization::ImageViewer::convertRGBCloudToUChar (
00055     const pcl::PointCloud<T> &cloud,
00056     boost::shared_array<unsigned char> &data)
00057 {
00058   int j = 0;
00059   for (size_t i = 0; i < cloud.points.size (); ++i)
00060   {
00061     data[j++] = cloud.points[i].r;
00062     data[j++] = cloud.points[i].g;
00063     data[j++] = cloud.points[i].b;
00064   }
00065 }
00066 
00068 template <typename T> void
00069 pcl::visualization::ImageViewer::addRGBImage (const pcl::PointCloud<T> &cloud,
00070                                               const std::string &layer_id,
00071                                               double opacity)
00072 {
00073   if (data_size_ < cloud.width * cloud.height)
00074   {
00075     data_size_ = cloud.width * cloud.height * 3;
00076     data_.reset (new unsigned char[data_size_]);
00077   }
00078 
00079   convertRGBCloudToUChar (cloud, data_);
00080 
00081   return (addRGBImage (data_.get (), cloud.width, cloud.height, layer_id, opacity));
00082 }
00083 
00085 template <typename T> void
00086 pcl::visualization::ImageViewer::showRGBImage (const pcl::PointCloud<T> &cloud,
00087                                                const std::string &layer_id,
00088                                                double opacity)
00089 {
00090   addRGBImage<T> (cloud, layer_id, opacity);
00091   render ();
00092 }
00093 
00095 template <typename T> bool
00096 pcl::visualization::ImageViewer::addMask (
00097     const typename pcl::PointCloud<T>::ConstPtr &image,
00098     const pcl::PointCloud<T> &mask, 
00099     double r, double g, double b,
00100     const std::string &layer_id, double opacity)
00101 {
00102   // We assume that the data passed into image is organized, otherwise this doesn't make sense
00103   if (!image->isOrganized ())
00104     return (false);
00105 
00106   // Check to see if this ID entry already exists (has it been already added to the visualizer?)
00107   LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00108   if (am_it == layer_map_.end ())
00109   {
00110     PCL_DEBUG ("[pcl::visualization::ImageViewer::addMask] No layer with ID'=%s' found. Creating new one...\n", layer_id.c_str ());
00111     am_it = createLayer (layer_id, getSize ()[0] - 1, getSize ()[1] - 1, opacity, true);
00112   }
00113 
00114   // Construct a search object to get the camera parameters
00115   pcl::search::OrganizedNeighbor<T> search;
00116   search.setInputCloud (image);
00117   std::vector<float> xy;
00118   xy.reserve (mask.size () * 2);
00119   const float image_height_f = static_cast<float> (image->height);
00120   for (size_t i = 0; i < mask.size (); ++i)
00121   {
00122     pcl::PointXY p_projected;
00123     search.projectPoint (mask[i], p_projected);
00124 
00125     xy.push_back (p_projected.x);
00126     #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 10))
00127     xy.push_back (image_height_f - p_projected.y);
00128     #else
00129     xy.push_back (p_projected.y);
00130     #endif
00131   }
00132 
00133   vtkSmartPointer<context_items::Points> points = vtkSmartPointer<context_items::Points>::New ();
00134   points->setColors (static_cast<unsigned char> (r*255.0), 
00135                      static_cast<unsigned char> (g*255.0), 
00136                      static_cast<unsigned char> (b*255.0));
00137   points->setOpacity (opacity);
00138   am_it->actor->GetScene ()->AddItem (points);
00139   return (true);
00140 }
00141 
00143 template <typename T> bool
00144 pcl::visualization::ImageViewer::addMask (
00145     const typename pcl::PointCloud<T>::ConstPtr &image,
00146     const pcl::PointCloud<T> &mask, 
00147     const std::string &layer_id, double opacity)
00148 {
00149   return (addMask (image, mask, 1.0, 0.0, 0.0, layer_id, opacity));
00150 }
00151 
00153 template <typename T> bool
00154 pcl::visualization::ImageViewer::addPlanarPolygon (
00155     const typename pcl::PointCloud<T>::ConstPtr &image,
00156     const pcl::PlanarPolygon<T> &polygon, 
00157     double r, double g, double b,
00158     const std::string &layer_id, double opacity)
00159 {
00160   // We assume that the data passed into image is organized, otherwise this doesn't make sense
00161   if (!image->isOrganized ())
00162     return (false);
00163 
00164   // Check to see if this ID entry already exists (has it been already added to the visualizer?)
00165   LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00166   if (am_it == layer_map_.end ())
00167   {
00168     PCL_DEBUG ("[pcl::visualization::ImageViewer::addPlanarPolygon] No layer with ID'=%s' found. Creating new one...\n", layer_id.c_str ());
00169     am_it = createLayer (layer_id, getSize ()[0] - 1, getSize ()[1] - 1, opacity, true);
00170   }
00171   
00172   // Construct a search object to get the camera parameters and fill points
00173   pcl::search::OrganizedNeighbor<T> search;
00174   search.setInputCloud (image);
00175   const float image_height_f = static_cast<float> (image->height);
00176   std::vector<float> xy;
00177   xy.reserve ((polygon.getContour ().size () + 1) * 2);
00178   for (size_t i = 0; i < polygon.getContour ().size (); ++i)
00179   {
00180     pcl::PointXY p;
00181     search.projectPoint (polygon.getContour ()[i], p);
00182     xy.push_back (p.x);
00183     #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 10))
00184     xy.push_back (image_height_f - p.y);
00185     #else
00186     xy.push_back (p.y);
00187     #endif
00188   }
00189 
00190   // Close the polygon
00191   xy[xy.size () - 2] = xy[0];
00192   xy[xy.size () - 1] = xy[1];
00193 
00194   vtkSmartPointer<context_items::Polygon> poly = vtkSmartPointer<context_items::Polygon>::New ();
00195   poly->setColors (static_cast<unsigned char> (r * 255.0), 
00196                    static_cast<unsigned char> (g * 255.0), 
00197                    static_cast<unsigned char> (b * 255.0));
00198   poly->set (xy);
00199   am_it->actor->GetScene ()->AddItem (poly);
00200 
00201   return (true);
00202 }
00203 
00205 template <typename T> bool
00206 pcl::visualization::ImageViewer::addPlanarPolygon (
00207     const typename pcl::PointCloud<T>::ConstPtr &image,
00208     const pcl::PlanarPolygon<T> &polygon, 
00209     const std::string &layer_id, double opacity)
00210 {
00211   return (addPlanarPolygon (image, polygon, 1.0, 0.0, 0.0, layer_id, opacity));
00212 }
00213 
00215 template <typename T> bool
00216 pcl::visualization::ImageViewer::addRectangle (
00217     const typename pcl::PointCloud<T>::ConstPtr &image,
00218     const T &min_pt,
00219     const T &max_pt,
00220     double r, double g, double b,
00221     const std::string &layer_id, double opacity)
00222 {
00223   // We assume that the data passed into image is organized, otherwise this doesn't make sense
00224   if (!image->isOrganized ())
00225     return (false);
00226 
00227   // Check to see if this ID entry already exists (has it been already added to the visualizer?)
00228   LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00229   if (am_it == layer_map_.end ())
00230   {
00231     PCL_DEBUG ("[pcl::visualization::ImageViewer::addRectangle] No layer with ID'=%s' found. Creating new one...\n", layer_id.c_str ());
00232     am_it = createLayer (layer_id, getSize ()[0] - 1, getSize ()[1] - 1, opacity, true);
00233   }
00234 
00235   // Construct a search object to get the camera parameters
00236   pcl::search::OrganizedNeighbor<T> search;
00237   search.setInputCloud (image);
00238   // Project the 8 corners
00239   T p1, p2, p3, p4, p5, p6, p7, p8;
00240   p1.x = min_pt.x; p1.y = min_pt.y; p1.z = min_pt.z;
00241   p2.x = min_pt.x; p2.y = min_pt.y; p2.z = max_pt.z;
00242   p3.x = min_pt.x; p3.y = max_pt.y; p3.z = min_pt.z;
00243   p4.x = min_pt.x; p4.y = max_pt.y; p4.z = max_pt.z;
00244   p5.x = max_pt.x; p5.y = min_pt.y; p5.z = min_pt.z;
00245   p6.x = max_pt.x; p6.y = min_pt.y; p6.z = max_pt.z;
00246   p7.x = max_pt.x; p7.y = max_pt.y; p7.z = min_pt.z;
00247   p8.x = max_pt.x; p8.y = max_pt.y; p8.z = max_pt.z;
00248 
00249   std::vector<pcl::PointXY> pp_2d (8);
00250   search.projectPoint (p1, pp_2d[0]);
00251   search.projectPoint (p2, pp_2d[1]);
00252   search.projectPoint (p3, pp_2d[2]);
00253   search.projectPoint (p4, pp_2d[3]);
00254   search.projectPoint (p5, pp_2d[4]);
00255   search.projectPoint (p6, pp_2d[5]);
00256   search.projectPoint (p7, pp_2d[6]);
00257   search.projectPoint (p8, pp_2d[7]);
00258 
00259   pcl::PointXY min_pt_2d, max_pt_2d;
00260   min_pt_2d.x = min_pt_2d.y = std::numeric_limits<float>::max ();
00261   max_pt_2d.x = max_pt_2d.y = std::numeric_limits<float>::min ();
00262   // Search for the two extrema
00263   for (size_t i = 0; i < pp_2d.size (); ++i)
00264   {
00265     if (pp_2d[i].x < min_pt_2d.x) min_pt_2d.x = pp_2d[i].x;
00266     if (pp_2d[i].y < min_pt_2d.y) min_pt_2d.y = pp_2d[i].y;
00267     if (pp_2d[i].x > max_pt_2d.x) max_pt_2d.x = pp_2d[i].x;
00268     if (pp_2d[i].y > max_pt_2d.y) max_pt_2d.y = pp_2d[i].y;
00269   }
00270 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 10))
00271   min_pt_2d.y = float (image->height) - min_pt_2d.y;
00272   max_pt_2d.y = float (image->height) - max_pt_2d.y;
00273 #endif
00274 
00275   vtkSmartPointer<context_items::Rectangle> rect = vtkSmartPointer<context_items::Rectangle>::New ();
00276   rect->setColors (static_cast<unsigned char> (255.0 * r), 
00277                    static_cast<unsigned char> (255.0 * g), 
00278                    static_cast<unsigned char> (255.0 * b));
00279   rect->setOpacity (opacity);
00280   rect->set (min_pt_2d.x, min_pt_2d.y, (max_pt_2d.x - min_pt_2d.x), (max_pt_2d.y - min_pt_2d.y));  
00281   am_it->actor->GetScene ()->AddItem (rect);
00282 
00283   return (true);
00284 }
00285 
00287 template <typename T> bool
00288 pcl::visualization::ImageViewer::addRectangle (
00289     const typename pcl::PointCloud<T>::ConstPtr &image,
00290     const T &min_pt,
00291     const T &max_pt,
00292     const std::string &layer_id, double opacity)
00293 {
00294   return (addRectangle<T> (image, min_pt, max_pt, 0.0, 1.0, 0.0, layer_id, opacity));
00295 }
00296 
00298 template <typename T> bool
00299 pcl::visualization::ImageViewer::addRectangle (
00300     const typename pcl::PointCloud<T>::ConstPtr &image,
00301     const pcl::PointCloud<T> &mask, 
00302     double r, double g, double b,
00303     const std::string &layer_id, double opacity)
00304 {
00305   // We assume that the data passed into image is organized, otherwise this doesn't make sense
00306   if (!image->isOrganized ())
00307     return (false);
00308 
00309   // Check to see if this ID entry already exists (has it been already added to the visualizer?)
00310   LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00311   if (am_it == layer_map_.end ())
00312   {
00313     PCL_DEBUG ("[pcl::visualization::ImageViewer::addRectangle] No layer with ID'=%s' found. Creating new one...\n", layer_id.c_str ());
00314     am_it = createLayer (layer_id, getSize ()[0] - 1, getSize ()[1] - 1, opacity, true);
00315   }
00316 
00317   // Construct a search object to get the camera parameters
00318   pcl::search::OrganizedNeighbor<T> search;
00319   search.setInputCloud (image);
00320   std::vector<pcl::PointXY> pp_2d (mask.points.size ());
00321   for (size_t i = 0; i < mask.points.size (); ++i)
00322     search.projectPoint (mask.points[i], pp_2d[i]);
00323 
00324   pcl::PointXY min_pt_2d, max_pt_2d;
00325   min_pt_2d.x = min_pt_2d.y = std::numeric_limits<float>::max ();
00326   max_pt_2d.x = max_pt_2d.y = std::numeric_limits<float>::min ();
00327   // Search for the two extrema
00328   for (size_t i = 0; i < pp_2d.size (); ++i)
00329   {
00330     if (pp_2d[i].x < min_pt_2d.x) min_pt_2d.x = pp_2d[i].x;
00331     if (pp_2d[i].y < min_pt_2d.y) min_pt_2d.y = pp_2d[i].y;
00332     if (pp_2d[i].x > max_pt_2d.x) max_pt_2d.x = pp_2d[i].x;
00333     if (pp_2d[i].y > max_pt_2d.y) max_pt_2d.y = pp_2d[i].y;
00334   }
00335 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 10))
00336   min_pt_2d.y = float (image->height) - min_pt_2d.y;
00337   max_pt_2d.y = float (image->height) - max_pt_2d.y;
00338 #endif
00339 
00340   vtkSmartPointer<context_items::Rectangle> rect = vtkSmartPointer<context_items::Rectangle>::New ();
00341   rect->setColors (static_cast<unsigned char> (255.0 * r), 
00342                    static_cast<unsigned char> (255.0 * g), 
00343                    static_cast<unsigned char> (255.0 * b));
00344   rect->setOpacity (opacity);
00345   rect->set (min_pt_2d.x, min_pt_2d.y, (max_pt_2d.x - min_pt_2d.x), (max_pt_2d.y - min_pt_2d.y));
00346   am_it->actor->GetScene ()->AddItem (rect);
00347 
00348   return (true);
00349 }
00350 
00352 template <typename T> bool
00353 pcl::visualization::ImageViewer::addRectangle (
00354     const typename pcl::PointCloud<T>::ConstPtr &image,
00355     const pcl::PointCloud<T> &mask, 
00356     const std::string &layer_id, double opacity)
00357 {
00358   return (addRectangle (image, mask, 0.0, 1.0, 0.0, layer_id, opacity));
00359 }
00360 
00362 template <typename PointT> bool
00363 pcl::visualization::ImageViewer::showCorrespondences (
00364   const pcl::PointCloud<PointT> &source_img,
00365   const pcl::PointCloud<PointT> &target_img,
00366   const pcl::Correspondences &correspondences,
00367   int nth,
00368   const std::string &layer_id)
00369 {
00370   if (correspondences.empty ())
00371   {
00372     PCL_DEBUG ("[pcl::visualization::ImageViewer::addCorrespondences] An empty set of correspondences given! Nothing to display.\n");
00373     return (false);
00374   }
00375 
00376   // Check to see if this ID entry already exists (has it been already added to the visualizer?)
00377   LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00378   if (am_it == layer_map_.end ())
00379   {
00380     PCL_DEBUG ("[pcl::visualization::ImageViewer::addCorrespondences] No layer with ID='%s' found. Creating new one...\n", layer_id.c_str ());
00381     am_it = createLayer (layer_id, source_img.width + target_img.width, std::max (source_img.height, target_img.height), 1.0, false);
00382   }
00383  
00384   int src_size = source_img.width * source_img.height * 3;
00385   int tgt_size = target_img.width * target_img.height * 3;
00386 
00387   // Set window size
00388   setSize (source_img.width + target_img.width , std::max (source_img.height, target_img.height));
00389 
00390   // Set data size
00391   if (data_size_ < (src_size + tgt_size))
00392   {
00393     data_size_ = src_size + tgt_size;
00394     data_.reset (new unsigned char[data_size_]);
00395   }
00396 
00397   // Copy data in VTK format
00398   int j = 0;
00399   for (size_t i = 0; i < std::max (source_img.height, target_img.height); ++i)
00400   {
00401     // Still need to copy the source?
00402     if (i < source_img.height)
00403     {
00404       for (size_t k = 0; k < source_img.width; ++k)
00405       {
00406         data_[j++] = source_img[i * source_img.width + k].r;
00407         data_[j++] = source_img[i * source_img.width + k].g;
00408         data_[j++] = source_img[i * source_img.width + k].b;
00409       }
00410     }
00411     else
00412     {
00413       memcpy (&data_[j], 0, source_img.width * 3);
00414       j += source_img.width * 3;
00415     }
00416 
00417     // Still need to copy the target?
00418     if (i < source_img.height)
00419     {
00420       for (size_t k = 0; k < target_img.width; ++k)
00421       {
00422         data_[j++] = target_img[i * source_img.width + k].r;
00423         data_[j++] = target_img[i * source_img.width + k].g;
00424         data_[j++] = target_img[i * source_img.width + k].b;
00425       }
00426     }
00427     else
00428     {
00429       memcpy (&data_[j], 0, target_img.width * 3);
00430       j += target_img.width * 3;
00431     }
00432   }
00433 
00434   void* data = const_cast<void*> (reinterpret_cast<const void*> (data_.get ()));
00435   
00436   vtkSmartPointer<vtkImageData> image = vtkSmartPointer<vtkImageData>::New ();
00437   image->SetDimensions (source_img.width + target_img.width, std::max (source_img.height, target_img.height), 1);
00438   image->SetScalarTypeToUnsignedChar ();
00439   image->SetNumberOfScalarComponents (3);
00440   image->AllocateScalars ();
00441   image->GetPointData ()->GetScalars ()->SetVoidArray (data, data_size_, 1);
00442   vtkSmartPointer<PCLContextImageItem> image_item = vtkSmartPointer<PCLContextImageItem>::New ();
00443 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 10))
00444   // Now create filter and set previously created transformation
00445   algo_->SetInput (image);
00446   algo_->Update ();
00447   image_item->set (0, 0, algo_->GetOutput ());
00448 #else
00449   image_item->set (0, 0, image);
00450   interactor_style_->adjustCamera (image, ren_);
00451 #endif
00452   am_it->actor->GetScene ()->AddItem (image_item);
00453   image_viewer_->SetSize (image->GetDimensions ()[0], image->GetDimensions ()[1]);
00454 
00455   // Draw lines between the best corresponding points
00456   for (size_t i = 0; i < correspondences.size (); i += nth)
00457   {
00458     double r, g, b;
00459     getRandomColors (r, g, b);
00460     unsigned char u_r = static_cast<unsigned char> (255.0 * r);
00461     unsigned char u_g = static_cast<unsigned char> (255.0 * g);
00462     unsigned char u_b = static_cast<unsigned char> (255.0 * b);
00463     vtkSmartPointer<context_items::Circle> query_circle = vtkSmartPointer<context_items::Circle>::New ();
00464     query_circle->setColors (u_r, u_g, u_b);
00465     vtkSmartPointer<context_items::Circle> match_circle = vtkSmartPointer<context_items::Circle>::New ();
00466     match_circle->setColors (u_r, u_g, u_b);
00467     vtkSmartPointer<context_items::Line> line = vtkSmartPointer<context_items::Line>::New ();
00468     line->setColors (u_r, u_g, u_b);
00469 
00470     float query_x = correspondences[i].index_query % source_img.width;
00471     float match_x = correspondences[i].index_match % target_img.width + source_img.width;
00472 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION > 10))
00473     float query_y = correspondences[i].index_query / source_img.width;
00474     float match_y = correspondences[i].index_match / target_img.width;
00475 #else
00476     float query_y = getSize ()[1] - correspondences[i].index_query / source_img.width;
00477     float match_y = getSize ()[1] - correspondences[i].index_match / target_img.width;
00478 #endif
00479 
00480     query_circle->set (query_x, query_y, 3.0);
00481     match_circle->set (match_x, match_y, 3.0);
00482     line->set (query_x, query_y, match_x, match_y);
00483 
00484     am_it->actor->GetScene ()->AddItem (query_circle);
00485     am_it->actor->GetScene ()->AddItem (match_circle);
00486     am_it->actor->GetScene ()->AddItem (line);
00487   }
00488   
00489   return (true);
00490 }
00491 
00492 #endif      // PCL_VISUALIZATION_IMAGE_VISUALIZER_HPP_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:24:58