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  *
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  * $Id: image_viewer.hpp 5629 2012-04-26 00:22:41Z rusu $
00037  */
00038 
00039 #ifndef PCL_VISUALIZATION_IMAGE_VISUALIZER_HPP_
00040 #define PCL_VISUALIZATION_IMAGE_VISUALIZER_HPP_
00041 
00042 #include <pcl/search/organized.h>
00043 
00045 template <typename T> void
00046 pcl::visualization::ImageViewer::showRGBImage (const pcl::PointCloud<T> &cloud,
00047                                                const std::string &layer_id,
00048                                                double opacity)
00049 {
00050   if (data_size_ < cloud.width * cloud.height)
00051   {
00052     data_size_ = cloud.width * cloud.height * 3;
00053     data_.reset (new unsigned char[data_size_]);
00054   }
00055   
00056   for (size_t i = 0; i < cloud.points.size (); ++i)
00057   {
00058     memcpy (&data_[i * 3], reinterpret_cast<const unsigned char*> (&cloud.points[i].rgba), sizeof (unsigned char) * 3);
00060     unsigned char aux = data_[i*3];
00061     data_[i*3] = data_[i*3+2];
00062     data_[i*3+2] = aux;
00063     for (int j = 0; j < 3; ++j)
00064       if (pcl_isnan (data_[i * 3 + j]))
00065           data_[i * 3 + j] = 0;
00066   }
00067   return (showRGBImage (data_.get (), cloud.width, cloud.height, layer_id, opacity));
00068 }
00069 
00071 template <typename T> void
00072 pcl::visualization::ImageViewer::addRGBImage (const pcl::PointCloud<T> &cloud,
00073                                               const std::string &layer_id,
00074                                               double opacity)
00075 {
00076   if (data_size_ < cloud.width * cloud.height)
00077   {
00078     data_size_ = cloud.width * cloud.height * 3;
00079     data_.reset (new unsigned char[data_size_]);
00080   }
00081   
00082   for (size_t i = 0; i < cloud.points.size (); ++i)
00083   {
00084     memcpy (&data_[i * 3], reinterpret_cast<const unsigned char*> (&cloud.points[i].rgba), sizeof (unsigned char) * 3);
00086     unsigned char aux = data_[i*3];
00087     data_[i*3] = data_[i*3+2];
00088     data_[i*3+2] = aux;
00089     for (int j = 0; j < 3; ++j)
00090       if (pcl_isnan (data_[i * 3 + j]))
00091           data_[i * 3 + j] = 0;
00092   }
00093   return (addRGBImage (data_.get (), cloud.width, cloud.height, layer_id, opacity));
00094 }
00095 
00097 template <typename T> bool
00098 pcl::visualization::ImageViewer::addMask (
00099     const typename pcl::PointCloud<T>::ConstPtr &image,
00100     const pcl::PointCloud<T> &mask, 
00101     double r, double g, double b,
00102     const std::string &layer_id, double opacity)
00103 {
00104   // We assume that the data passed into image is organized, otherwise this doesn't make sense
00105   if (!image->isOrganized ())
00106     return (false);
00107 
00108   // Check to see if this ID entry already exists (has it been already added to the visualizer?)
00109   LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00110   if (am_it == layer_map_.end ())
00111   {
00112     PCL_DEBUG ("[pcl::visualization::ImageViewer::addMask] No layer with ID'=%s' found. Creating new one...\n", layer_id.c_str ());
00113     am_it = createLayer (layer_id, image_viewer_->GetRenderWindow ()->GetSize ()[0] - 1, image_viewer_->GetRenderWindow ()->GetSize ()[1] - 1, opacity, true);
00114   }
00115 
00116   am_it->canvas->SetDrawColor (r * 255.0, g * 255.0, b * 255.0, opacity * 255.0);
00117 
00118   // Construct a search object to get the camera parameters
00119   pcl::search::OrganizedNeighbor<T> search;
00120   search.setInputCloud (image);
00121   for (size_t i = 0; i < mask.points.size (); ++i)
00122   {
00123     pcl::PointXY p_projected;
00124     search.projectPoint (mask.points[i], p_projected);
00125 
00126     am_it->canvas->DrawPoint (int (p_projected.x), 
00127                               int (float (image->height) - p_projected.y));
00128   }
00129 
00130   return (true);
00131 }
00132 
00134 template <typename T> bool
00135 pcl::visualization::ImageViewer::addMask (
00136     const typename pcl::PointCloud<T>::ConstPtr &image,
00137     const pcl::PointCloud<T> &mask, 
00138     const std::string &layer_id, double opacity)
00139 {
00140   // We assume that the data passed into image is organized, otherwise this doesn't make sense
00141   if (!image->isOrganized ())
00142     return (false);
00143 
00144   // Check to see if this ID entry already exists (has it been already added to the visualizer?)
00145   LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00146   if (am_it == layer_map_.end ())
00147   {
00148     PCL_DEBUG ("[pcl::visualization::ImageViewer::addMask] No layer with ID'=%s' found. Creating new one...\n", layer_id.c_str ());
00149     am_it = createLayer (layer_id, image_viewer_->GetRenderWindow ()->GetSize ()[0] - 1, image_viewer_->GetRenderWindow ()->GetSize ()[1] - 1, opacity, true);
00150   }
00151 
00152   am_it->canvas->SetDrawColor (255.0, 0.0, 0.0, opacity * 255.0);
00153 
00154   // Construct a search object to get the camera parameters
00155   pcl::search::OrganizedNeighbor<T> search;
00156   search.setInputCloud (image);
00157   for (size_t i = 0; i < mask.points.size (); ++i)
00158   {
00159     pcl::PointXY p_projected;
00160     search.projectPoint (mask.points[i], p_projected);
00161 
00162     am_it->canvas->DrawPoint (int (p_projected.x), 
00163                               int (float (image->height) - p_projected.y));
00164   }
00165 
00166   return (true);
00167 }
00168 
00170 template <typename T> bool
00171 pcl::visualization::ImageViewer::addPlanarPolygon (
00172     const typename pcl::PointCloud<T>::ConstPtr &image,
00173     const pcl::PlanarPolygon<T> &polygon, 
00174     double r, double g, double b,
00175     const std::string &layer_id, double opacity)
00176 {
00177   // We assume that the data passed into image is organized, otherwise this doesn't make sense
00178   if (!image->isOrganized ())
00179     return (false);
00180 
00181   // Check to see if this ID entry already exists (has it been already added to the visualizer?)
00182   LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00183   if (am_it == layer_map_.end ())
00184   {
00185     PCL_DEBUG ("[pcl::visualization::ImageViewer::addPlanarPolygon] No layer with ID'=%s' found. Creating new one...\n", layer_id.c_str ());
00186     am_it = createLayer (layer_id, image_viewer_->GetRenderWindow ()->GetSize ()[0] - 1, image_viewer_->GetRenderWindow ()->GetSize ()[1] - 1, opacity, true);
00187   }
00188 
00189   am_it->canvas->SetDrawColor (r * 255.0, g * 255.0, b * 255.0, opacity * 255.0);
00190 
00191   // Construct a search object to get the camera parameters
00192   pcl::search::OrganizedNeighbor<T> search;
00193   search.setInputCloud (image);
00194   for (size_t i = 0; i < polygon.getContour ().size () - 1; ++i)
00195   {
00196     pcl::PointXY p1, p2;
00197     search.projectPoint (polygon.getContour ()[i], p1);
00198     search.projectPoint (polygon.getContour ()[i+1], p2);
00199 
00200     am_it->canvas->DrawSegment (int (p1.x), int (float (image->height) - p1.y),
00201                                 int (p2.x), int (float (image->height) - p2.y));
00202   }
00203 
00204   // Close the polygon
00205   pcl::PointXY p1, p2;
00206   search.projectPoint (polygon.getContour ()[polygon.getContour ().size () - 1], p1);
00207   search.projectPoint (polygon.getContour ()[0], p2);
00208 
00209   am_it->canvas->DrawSegment (int (p1.x), int (float (image->height) - p1.y),
00210                               int (p2.x), int (float (image->height) - p2.y));
00211  
00212   return (true);
00213 }
00214 
00216 template <typename T> bool
00217 pcl::visualization::ImageViewer::addPlanarPolygon (
00218     const typename pcl::PointCloud<T>::ConstPtr &image,
00219     const pcl::PlanarPolygon<T> &polygon, 
00220     const std::string &layer_id, double opacity)
00221 {
00222   // We assume that the data passed into image is organized, otherwise this doesn't make sense
00223   if (!image->isOrganized ())
00224     return (false);
00225 
00226   // Check to see if this ID entry already exists (has it been already added to the visualizer?)
00227   LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00228   if (am_it == layer_map_.end ())
00229   {
00230     PCL_DEBUG ("[pcl::visualization::ImageViewer::addPlanarPolygon] No layer with ID'=%s' found. Creating new one...\n", layer_id.c_str ());
00231     am_it = createLayer (layer_id, image_viewer_->GetRenderWindow ()->GetSize ()[0] - 1, image_viewer_->GetRenderWindow ()->GetSize ()[1] - 1, opacity, true);
00232   }
00233 
00234   am_it->canvas->SetDrawColor (255.0, 0.0, 0.0, opacity * 255.0);
00235 
00236   // Construct a search object to get the camera parameters
00237   pcl::search::OrganizedNeighbor<T> search;
00238   search.setInputCloud (image);
00239   for (size_t i = 0; i < polygon.getContour ().size () - 1; ++i)
00240   {
00241     pcl::PointXY p1, p2;
00242     search.projectPoint (polygon.getContour ()[i], p1);
00243     search.projectPoint (polygon.getContour ()[i+1], p2);
00244 
00245     am_it->canvas->DrawSegment (int (p1.x), int (float (image->height) - p1.y),
00246                                 int (p2.x), int (float (image->height) - p2.y));
00247   }
00248 
00249   // Close the polygon
00250   pcl::PointXY p1, p2;
00251   search.projectPoint (polygon.getContour ()[polygon.getContour ().size () - 1], p1);
00252   search.projectPoint (polygon.getContour ()[0], p2);
00253 
00254   am_it->canvas->DrawSegment (int (p1.x), int (float (image->height) - p1.y),
00255                               int (p2.x), int (float (image->height) - p2.y));
00256   return (true);
00257 }
00258 
00260 template <typename T> bool
00261 pcl::visualization::ImageViewer::addRectangle (
00262     const typename pcl::PointCloud<T>::ConstPtr &image,
00263     const T &min_pt,
00264     const T &max_pt,
00265     double r, double g, double b,
00266     const std::string &layer_id, double opacity)
00267 {
00268   // We assume that the data passed into image is organized, otherwise this doesn't make sense
00269   if (!image->isOrganized ())
00270     return (false);
00271 
00272   // Check to see if this ID entry already exists (has it been already added to the visualizer?)
00273   LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00274   if (am_it == layer_map_.end ())
00275   {
00276     PCL_DEBUG ("[pcl::visualization::ImageViewer::addRectangle] No layer with ID'=%s' found. Creating new one...\n", layer_id.c_str ());
00277     am_it = createLayer (layer_id, image_viewer_->GetRenderWindow ()->GetSize ()[0] - 1, image_viewer_->GetRenderWindow ()->GetSize ()[1] - 1, opacity, true);
00278   }
00279 
00280   // Construct a search object to get the camera parameters
00281   pcl::search::OrganizedNeighbor<T> search;
00282   search.setInputCloud (image);
00283   // Project the 8 corners
00284   T p1, p2, p3, p4, p5, p6, p7, p8;
00285   p1.x = min_pt.x; p1.y = min_pt.y; p1.z = min_pt.z;
00286   p2.x = min_pt.x; p2.y = min_pt.y; p2.z = max_pt.z;
00287   p3.x = min_pt.x; p3.y = max_pt.y; p3.z = min_pt.z;
00288   p4.x = min_pt.x; p4.y = max_pt.y; p4.z = max_pt.z;
00289   p5.x = max_pt.x; p5.y = min_pt.y; p5.z = min_pt.z;
00290   p6.x = max_pt.x; p6.y = min_pt.y; p6.z = max_pt.z;
00291   p7.x = max_pt.x; p7.y = max_pt.y; p7.z = min_pt.z;
00292   p8.x = max_pt.x; p8.y = max_pt.y; p8.z = max_pt.z;
00293 
00294   std::vector<pcl::PointXY> pp_2d (8);
00295   search.projectPoint (p1, pp_2d[0]);
00296   search.projectPoint (p2, pp_2d[1]);
00297   search.projectPoint (p3, pp_2d[2]);
00298   search.projectPoint (p4, pp_2d[3]);
00299   search.projectPoint (p5, pp_2d[4]);
00300   search.projectPoint (p6, pp_2d[5]);
00301   search.projectPoint (p7, pp_2d[6]);
00302   search.projectPoint (p8, pp_2d[7]);
00303 
00304   pcl::PointXY min_pt_2d, max_pt_2d;
00305   min_pt_2d.x = min_pt_2d.y = std::numeric_limits<float>::max ();
00306   max_pt_2d.x = max_pt_2d.y = std::numeric_limits<float>::min ();
00307   // Search for the two extrema
00308   for (size_t i = 0; i < pp_2d.size (); ++i)
00309   {
00310     if (pp_2d[i].x < min_pt_2d.x) min_pt_2d.x = pp_2d[i].x;
00311     if (pp_2d[i].y < min_pt_2d.y) min_pt_2d.y = pp_2d[i].y;
00312     if (pp_2d[i].x > max_pt_2d.x) max_pt_2d.x = pp_2d[i].x;
00313     if (pp_2d[i].y > max_pt_2d.y) max_pt_2d.y = pp_2d[i].y;
00314   }
00315   min_pt_2d.y = float (image->height) - min_pt_2d.y;
00316   max_pt_2d.y = float (image->height) - max_pt_2d.y;
00317 
00318   am_it->canvas->SetDrawColor (r * 255.0, g * 255.0, b * 255.0, opacity * 255.0);
00319 
00320   am_it->canvas->DrawSegment (int (min_pt_2d.x), int (min_pt_2d.y), int (min_pt_2d.x), int (max_pt_2d.y));
00321   am_it->canvas->DrawSegment (int (min_pt_2d.x), int (max_pt_2d.y), int (max_pt_2d.x), int (max_pt_2d.y));
00322   am_it->canvas->DrawSegment (int (max_pt_2d.x), int (max_pt_2d.y), int (max_pt_2d.x), int (min_pt_2d.y));
00323   am_it->canvas->DrawSegment (int (max_pt_2d.x), int (min_pt_2d.y), int (min_pt_2d.x), int (min_pt_2d.y));
00324 
00325   return (true);
00326 }
00327 
00329 template <typename T> bool
00330 pcl::visualization::ImageViewer::addRectangle (
00331     const typename pcl::PointCloud<T>::ConstPtr &image,
00332     const T &min_pt,
00333     const T &max_pt,
00334     const std::string &layer_id, double opacity)
00335 {
00336   // We assume that the data passed into image is organized, otherwise this doesn't make sense
00337   if (!image->isOrganized ())
00338     return (false);
00339 
00340   // Check to see if this ID entry already exists (has it been already added to the visualizer?)
00341   LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00342   if (am_it == layer_map_.end ())
00343   {
00344     PCL_DEBUG ("[pcl::visualization::ImageViewer::addRectangle] No layer with ID'=%s' found. Creating new one...\n", layer_id.c_str ());
00345     am_it = createLayer (layer_id, image_viewer_->GetRenderWindow ()->GetSize ()[0] - 1, image_viewer_->GetRenderWindow ()->GetSize ()[1] - 1, opacity, true);
00346   }
00347 
00348   // Construct a search object to get the camera parameters
00349   pcl::search::OrganizedNeighbor<T> search;
00350   search.setInputCloud (image);
00351   // Project the 8 corners
00352   T p1, p2, p3, p4, p5, p6, p7, p8;
00353   p1.x = min_pt.x; p1.y = min_pt.y; p1.z = min_pt.z;
00354   p2.x = min_pt.x; p2.y = min_pt.y; p2.z = max_pt.z;
00355   p3.x = min_pt.x; p3.y = max_pt.y; p3.z = min_pt.z;
00356   p4.x = min_pt.x; p4.y = max_pt.y; p4.z = max_pt.z;
00357   p5.x = max_pt.x; p5.y = min_pt.y; p5.z = min_pt.z;
00358   p6.x = max_pt.x; p6.y = min_pt.y; p6.z = max_pt.z;
00359   p7.x = max_pt.x; p7.y = max_pt.y; p7.z = min_pt.z;
00360   p8.x = max_pt.x; p8.y = max_pt.y; p8.z = max_pt.z;
00361 
00362   std::vector<pcl::PointXY> pp_2d (8);
00363   search.projectPoint (p1, pp_2d[0]);
00364   search.projectPoint (p2, pp_2d[1]);
00365   search.projectPoint (p3, pp_2d[2]);
00366   search.projectPoint (p4, pp_2d[3]);
00367   search.projectPoint (p5, pp_2d[4]);
00368   search.projectPoint (p6, pp_2d[5]);
00369   search.projectPoint (p7, pp_2d[6]);
00370   search.projectPoint (p8, pp_2d[7]);
00371 
00372   pcl::PointXY min_pt_2d, max_pt_2d;
00373   min_pt_2d.x = min_pt_2d.y = std::numeric_limits<float>::max ();
00374   max_pt_2d.x = max_pt_2d.y = std::numeric_limits<float>::min ();
00375   // Search for the two extrema
00376   for (size_t i = 0; i < pp_2d.size (); ++i)
00377   {
00378     if (pp_2d[i].x < min_pt_2d.x) min_pt_2d.x = pp_2d[i].x;
00379     if (pp_2d[i].y < min_pt_2d.y) min_pt_2d.y = pp_2d[i].y;
00380     if (pp_2d[i].x > max_pt_2d.x) max_pt_2d.x = pp_2d[i].x;
00381     if (pp_2d[i].y > max_pt_2d.y) max_pt_2d.y = pp_2d[i].y;
00382   }
00383   min_pt_2d.y = float (image->height) - min_pt_2d.y;
00384   max_pt_2d.y = float (image->height) - max_pt_2d.y;
00385 
00386   am_it->canvas->SetDrawColor (0.0, 255.0, 0.0, opacity * 255.0);
00387   am_it->canvas->DrawSegment (int (min_pt_2d.x), int (min_pt_2d.y), int (min_pt_2d.x), int (max_pt_2d.y));
00388   am_it->canvas->DrawSegment (int (min_pt_2d.x), int (max_pt_2d.y), int (max_pt_2d.x), int (max_pt_2d.y));
00389   am_it->canvas->DrawSegment (int (max_pt_2d.x), int (max_pt_2d.y), int (max_pt_2d.x), int (min_pt_2d.y));
00390   am_it->canvas->DrawSegment (int (max_pt_2d.x), int (min_pt_2d.y), int (min_pt_2d.x), int (min_pt_2d.y));
00391 
00392   return (true);
00393 }
00394 
00396 template <typename T> bool
00397 pcl::visualization::ImageViewer::addRectangle (
00398     const typename pcl::PointCloud<T>::ConstPtr &image,
00399     const pcl::PointCloud<T> &mask, 
00400     double r, double g, double b,
00401     const std::string &layer_id, double opacity)
00402 {
00403   // We assume that the data passed into image is organized, otherwise this doesn't make sense
00404   if (!image->isOrganized ())
00405     return (false);
00406 
00407   // Check to see if this ID entry already exists (has it been already added to the visualizer?)
00408   LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00409   if (am_it == layer_map_.end ())
00410   {
00411     PCL_DEBUG ("[pcl::visualization::ImageViewer::addRectangle] No layer with ID'=%s' found. Creating new one...\n", layer_id.c_str ());
00412     am_it = createLayer (layer_id, image_viewer_->GetRenderWindow ()->GetSize ()[0] - 1, image_viewer_->GetRenderWindow ()->GetSize ()[1] - 1, opacity, true);
00413   }
00414 
00415   am_it->canvas->SetDrawColor (r * 255.0, g * 255.0, b * 255.0, opacity * 255.0);
00416 
00417   // Construct a search object to get the camera parameters
00418   pcl::search::OrganizedNeighbor<T> search;
00419   search.setInputCloud (image);
00420   std::vector<pcl::PointXY> pp_2d (mask.points.size ());
00421   for (size_t i = 0; i < mask.points.size (); ++i)
00422     search.projectPoint (mask.points[i], pp_2d[i]);
00423 
00424   pcl::PointXY min_pt_2d, max_pt_2d;
00425   min_pt_2d.x = min_pt_2d.y = std::numeric_limits<float>::max ();
00426   max_pt_2d.x = max_pt_2d.y = std::numeric_limits<float>::min ();
00427   // Search for the two extrema
00428   for (size_t i = 0; i < pp_2d.size (); ++i)
00429   {
00430     if (pp_2d[i].x < min_pt_2d.x) min_pt_2d.x = pp_2d[i].x;
00431     if (pp_2d[i].y < min_pt_2d.y) min_pt_2d.y = pp_2d[i].y;
00432     if (pp_2d[i].x > max_pt_2d.x) max_pt_2d.x = pp_2d[i].x;
00433     if (pp_2d[i].y > max_pt_2d.y) max_pt_2d.y = pp_2d[i].y;
00434   }
00435   min_pt_2d.y = float (image->height) - min_pt_2d.y;
00436   max_pt_2d.y = float (image->height) - max_pt_2d.y;
00437 
00438   am_it->canvas->DrawSegment (int (min_pt_2d.x), int (min_pt_2d.y), int (min_pt_2d.x), int (max_pt_2d.y));
00439   am_it->canvas->DrawSegment (int (min_pt_2d.x), int (max_pt_2d.y), int (max_pt_2d.x), int (max_pt_2d.y));
00440   am_it->canvas->DrawSegment (int (max_pt_2d.x), int (max_pt_2d.y), int (max_pt_2d.x), int (min_pt_2d.y));
00441   am_it->canvas->DrawSegment (int (max_pt_2d.x), int (min_pt_2d.y), int (min_pt_2d.x), int (min_pt_2d.y));
00442 
00443   return (true);
00444 }
00445 
00447 template <typename T> bool
00448 pcl::visualization::ImageViewer::addRectangle (
00449     const typename pcl::PointCloud<T>::ConstPtr &image,
00450     const pcl::PointCloud<T> &mask, 
00451     const std::string &layer_id, double opacity)
00452 {
00453   // We assume that the data passed into image is organized, otherwise this doesn't make sense
00454   if (!image->isOrganized ())
00455     return (false);
00456 
00457   // Check to see if this ID entry already exists (has it been already added to the visualizer?)
00458   LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00459   if (am_it == layer_map_.end ())
00460   {
00461     PCL_DEBUG ("[pcl::visualization::ImageViewer::addRectangle] No layer with ID'=%s' found. Creating new one...\n", layer_id.c_str ());
00462     am_it = createLayer (layer_id, image_viewer_->GetRenderWindow ()->GetSize ()[0] - 1, image_viewer_->GetRenderWindow ()->GetSize ()[1] - 1, opacity, true);
00463   }
00464 
00465   am_it->canvas->SetDrawColor (0.0, 255.0, 0.0, opacity * 255.0);
00466 
00467   // Construct a search object to get the camera parameters
00468   pcl::search::OrganizedNeighbor<T> search;
00469   search.setInputCloud (image);
00470   std::vector<pcl::PointXY> pp_2d (mask.points.size ());
00471   for (size_t i = 0; i < mask.points.size (); ++i)
00472     search.projectPoint (mask.points[i], pp_2d[i]);
00473 
00474   pcl::PointXY min_pt_2d, max_pt_2d;
00475   min_pt_2d.x = min_pt_2d.y = std::numeric_limits<float>::max ();
00476   max_pt_2d.x = max_pt_2d.y = std::numeric_limits<float>::min ();
00477   // Search for the two extrema
00478   for (size_t i = 0; i < pp_2d.size (); ++i)
00479   {
00480     if (pp_2d[i].x < min_pt_2d.x) min_pt_2d.x = pp_2d[i].x;
00481     if (pp_2d[i].y < min_pt_2d.y) min_pt_2d.y = pp_2d[i].y;
00482     if (pp_2d[i].x > max_pt_2d.x) max_pt_2d.x = pp_2d[i].x;
00483     if (pp_2d[i].y > max_pt_2d.y) max_pt_2d.y = pp_2d[i].y;
00484   }
00485   min_pt_2d.y = float (image->height) - min_pt_2d.y;
00486   max_pt_2d.y = float (image->height) - max_pt_2d.y;
00487 
00488   am_it->canvas->DrawSegment (int (min_pt_2d.x), int (min_pt_2d.y), int (min_pt_2d.x), int (max_pt_2d.y));
00489   am_it->canvas->DrawSegment (int (min_pt_2d.x), int (max_pt_2d.y), int (max_pt_2d.x), int (max_pt_2d.y));
00490   am_it->canvas->DrawSegment (int (max_pt_2d.x), int (max_pt_2d.y), int (max_pt_2d.x), int (min_pt_2d.y));
00491   am_it->canvas->DrawSegment (int (max_pt_2d.x), int (min_pt_2d.y), int (min_pt_2d.x), int (min_pt_2d.y));
00492 
00493 
00494   return (true);
00495 }
00496 
00497 #endif      // PCL_VISUALIZATION_IMAGE_VISUALIZER_HPP_


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:26