$search
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage, Inc. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 * 00034 * $Id: pcl_visualizer.hpp 36905 2011-05-27 00:34:09Z michael.s.dixon $ 00035 * 00036 */ 00037 00039 template <typename PointT> bool 00040 pcl_visualization::PCLVisualizer::addPointCloud (const pcl::PointCloud<PointT> &cloud, 00041 const std::string &id, int viewport) 00042 { 00043 // Check to see if this ID entry already exists (has it been already added to the visualizer?) 00044 CloudActorMap::iterator am_it = cloud_actor_map_.find (id); 00045 00046 if (am_it != cloud_actor_map_.end ()) 00047 { 00048 pcl::console::print_warn ("[addPointCloud] A PointCloud with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); 00049 return (false); 00050 } 00051 vtkSmartPointer<vtkPolyData> polydata; 00052 00053 // Convert the PointCloud to VTK PolyData 00054 PointCloudGeometryHandlerXYZ<PointT> geometry_handler (cloud); 00055 if (!geometry_handler.isCapable ()) 00056 { 00057 pcl::console::print_warn ("[addPointCloud] A PointCloud with id <%s> requested with an invalid handler (%s)!\n", id.c_str (), geometry_handler.getName ().c_str ()); 00058 return (false); 00059 } 00060 00061 convertPointCloudToVTKPolyData<PointT> (geometry_handler, polydata); 00062 polydata->Update (); 00063 00064 // Get the colors from the handler 00065 vtkSmartPointer<vtkDataArray> scalars; 00066 PointCloudColorHandlerRandom<PointT> handler (cloud); 00067 handler.getColor (scalars); 00068 polydata->GetPointData ()->SetScalars (scalars); 00069 00070 // Create an Actor 00071 vtkSmartPointer<vtkLODActor> actor; 00072 createActorFromVTKDataSet (polydata, actor); 00073 00074 // Add it to all renderers 00075 addActorToRenderer (actor, viewport); 00076 00077 // Save the pointer/ID pair to the global actor map 00078 CloudActor act; 00079 act.actor = actor; 00080 //cloud_actor_map_[id] = actor; 00081 cloud_actor_map_[id] = act; 00082 style_->setCloudActorMap (boost::make_shared<CloudActorMap> (cloud_actor_map_)); 00083 return (true); 00084 } 00085 00087 template <typename PointT> bool 00088 pcl_visualization::PCLVisualizer::addPointCloud (const pcl::PointCloud<PointT> &cloud, 00089 const PointCloudGeometryHandler<PointT> &geometry_handler, 00090 const std::string &id, int viewport) 00091 { 00092 if (!geometry_handler.isCapable ()) 00093 { 00094 pcl::console::print_warn ("[addPointCloud] A PointCloud with id <%s> requested with an invalid handler (%s)!\n", id.c_str (), geometry_handler.getName ().c_str ()); 00095 return (false); 00096 } 00097 00098 // Check to see if this ID entry already exists (has it been already added to the visualizer?) 00099 CloudActorMap::iterator am_it = cloud_actor_map_.find (id); 00100 00101 if (am_it != cloud_actor_map_.end ()) 00102 { 00103 pcl::console::print_warn ("[addPointCloud] A PointCloud with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); 00104 return (false); 00105 } 00106 vtkSmartPointer<vtkPolyData> polydata; 00107 00108 // Convert the PointCloud to VTK PolyData 00109 convertPointCloudToVTKPolyData<PointT> (geometry_handler, polydata); // use the given geometry handler 00110 polydata->Update (); 00111 00112 // Get the colors from the handler 00113 vtkSmartPointer<vtkDataArray> scalars; 00114 PointCloudColorHandlerRandom<PointT> handler (cloud); 00115 handler.getColor (scalars); 00116 polydata->GetPointData ()->SetScalars (scalars); 00117 00118 // Create an Actor 00119 vtkSmartPointer<vtkLODActor> actor; 00120 createActorFromVTKDataSet (polydata, actor); 00121 00122 // Add it to all renderers 00123 addActorToRenderer (actor, viewport); 00124 00125 // Save the pointer/ID pair to the global actor map 00126 CloudActor act; 00127 act.actor = actor; 00128 //cloud_actor_map_[id] = actor; 00129 cloud_actor_map_[id] = act; 00130 style_->setCloudActorMap (boost::make_shared<CloudActorMap> (cloud_actor_map_)); 00131 return (true); 00132 } 00133 00135 template <typename PointT> bool 00136 pcl_visualization::PCLVisualizer::addPointCloud (const pcl::PointCloud<PointT> &cloud, 00137 const GeometryHandlerConstPtr &geometry_handler, 00138 const std::string &id, int viewport) 00139 { 00140 if (!geometry_handler->isCapable ()) 00141 { 00142 pcl::console::print_warn ("[addPointCloud] A PointCloud with id <%s> requested with an invalid handler (%s)!\n", id.c_str (), geometry_handler->getName ().c_str ()); 00143 return (false); 00144 } 00145 00146 // Check to see if this ID entry already exists (has it been already added to the visualizer?) 00147 CloudActorMap::iterator am_it = cloud_actor_map_.find (id); 00148 00149 if (am_it != cloud_actor_map_.end ()) 00150 { 00151 // Here we're just pushing the handlers onto the queue. If needed, something fancier could 00152 // be done such as checking if a specific handler already exists, etc. 00153 cloud_actor_map_[id].geometry_handlers.push_back (geometry_handler); 00154 style_->setCloudActorMap (boost::make_shared<CloudActorMap> (cloud_actor_map_)); 00155 return (true); 00156 } 00157 vtkSmartPointer<vtkPolyData> polydata; 00158 00159 // Convert the PointCloud to VTK PolyData 00160 convertPointCloudToVTKPolyData (geometry_handler, polydata); // use the given geometry handler 00161 polydata->Update (); 00162 00163 // Get the colors from the handler 00164 vtkSmartPointer<vtkDataArray> scalars; 00165 PointCloudColorHandlerRandom<PointT> handler (cloud); 00166 handler.getColor (scalars); 00167 polydata->GetPointData ()->SetScalars (scalars); 00168 00169 // Create an Actor 00170 vtkSmartPointer<vtkLODActor> actor; 00171 createActorFromVTKDataSet (polydata, actor); 00172 00173 // Add it to all renderers 00174 addActorToRenderer (actor, viewport); 00175 00176 // Save the pointer/ID pair to the global actor map 00177 CloudActor act; 00178 act.actor = actor; 00179 //cloud_actor_map_[id] = actor; 00180 cloud_actor_map_[id] = act; 00181 style_->setCloudActorMap (boost::make_shared<CloudActorMap> (cloud_actor_map_)); 00182 return (true); 00183 } 00184 00186 template <typename PointT> bool 00187 pcl_visualization::PCLVisualizer::addPointCloud (const pcl::PointCloud<PointT> &cloud, 00188 const PointCloudColorHandler<PointT> &color_handler, 00189 const std::string &id, int viewport) 00190 { 00191 if (!color_handler.isCapable ()) 00192 { 00193 pcl::console::print_warn ("[addPointCloud] A PointCloud with id <%s> requested with an invalid handler (%s)!\n", id.c_str (), color_handler.getName ().c_str ()); 00194 return (false); 00195 } 00196 00197 // Convert the PointCloud to VTK PolyData 00198 PointCloudGeometryHandlerXYZ<PointT> geometry_handler (cloud); 00199 if (!geometry_handler.isCapable ()) 00200 { 00201 pcl::console::print_warn ("[addPointCloud] A PointCloud with id <%s> requested with an invalid handler (%s)!\n", id.c_str (), geometry_handler.getName ().c_str ()); 00202 return (false); 00203 } 00204 00205 // Check to see if this ID entry already exists (has it been already added to the visualizer?) 00206 CloudActorMap::iterator am_it = cloud_actor_map_.find (id); 00207 00208 if (am_it != cloud_actor_map_.end ()) 00209 { 00210 pcl::console::print_warn ("[addPointCloud] A PointCloud with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); 00211 00212 // Here we're just pushing the handlers onto the queue. If needed, something fancier could 00213 // be done such as checking if a specific handler already exists, etc. 00214 //cloud_actor_map_[id].color_handlers.push_back (color_handler); 00215 //style_->setCloudActorMap (boost::make_shared<CloudActorMap> (cloud_actor_map_)); 00216 return (false); 00217 } 00218 vtkSmartPointer<vtkPolyData> polydata; 00219 00220 convertPointCloudToVTKPolyData<PointT> (geometry_handler, polydata); 00221 polydata->Update (); 00222 00223 // Get the colors from the handler 00224 vtkSmartPointer<vtkDataArray> scalars; 00225 color_handler.getColor (scalars); 00226 polydata->GetPointData ()->SetScalars (scalars); 00227 00228 // Create an Actor 00229 vtkSmartPointer<vtkLODActor> actor; 00230 createActorFromVTKDataSet (polydata, actor); 00231 00232 // Add it to all renderers 00233 addActorToRenderer (actor, viewport); 00234 00235 // Save the pointer/ID pair to the global actor map 00236 CloudActor act; 00237 act.actor = actor; 00238 //cloud_actor_map_[id] = actor; 00239 cloud_actor_map_[id] = act; 00240 style_->setCloudActorMap (boost::make_shared<CloudActorMap> (cloud_actor_map_)); 00241 return (true); 00242 } 00243 00245 template <typename PointT> bool 00246 pcl_visualization::PCLVisualizer::addPointCloud (const pcl::PointCloud<PointT> &cloud, 00247 const ColorHandlerConstPtr &color_handler, 00248 const std::string &id, int viewport) 00249 { 00250 if (!color_handler->isCapable ()) 00251 { 00252 pcl::console::print_warn ("[addPointCloud] A PointCloud with id <%s> requested with an invalid handler (%s)!\n", id.c_str (), color_handler->getName ().c_str ()); 00253 return (false); 00254 } 00255 00256 // Convert the PointCloud to VTK PolyData 00257 PointCloudGeometryHandlerXYZ<PointT> geometry_handler (cloud); 00258 if (!geometry_handler.isCapable ()) 00259 { 00260 pcl::console::print_warn ("[addPointCloud] A PointCloud with id <%s> requested with an invalid handler (%s)!\n", id.c_str (), geometry_handler.getName ().c_str ()); 00261 return (false); 00262 } 00263 00264 // Check to see if this entry already exists (has it been already added to the visualizer?) 00265 CloudActorMap::iterator am_it = cloud_actor_map_.find (id); 00266 if (am_it != cloud_actor_map_.end ()) 00267 { 00268 //pcl::console::print_warn ("[addPointCloud] A PointCloud with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); 00269 00270 // Here we're just pushing the handlers onto the queue. If needed, something fancier could 00271 // be done such as checking if a specific handler already exists, etc. 00272 cloud_actor_map_[id].color_handlers.push_back (color_handler); 00273 style_->setCloudActorMap (boost::make_shared<CloudActorMap> (cloud_actor_map_)); 00274 00275 return (true); 00276 } 00277 vtkSmartPointer<vtkPolyData> polydata; 00278 00279 convertPointCloudToVTKPolyData<PointT> (geometry_handler, polydata); 00280 polydata->Update (); 00281 00282 // Get the colors from the handler 00283 vtkSmartPointer<vtkDataArray> scalars; 00284 color_handler->getColor (scalars); 00285 polydata->GetPointData ()->SetScalars (scalars); 00286 00287 // Create an Actor 00288 vtkSmartPointer<vtkLODActor> actor; 00289 createActorFromVTKDataSet (polydata, actor); 00290 00291 // Add it to all renderers 00292 addActorToRenderer (actor, viewport); 00293 00294 // Save the pointer/ID pair to the global actor map 00295 CloudActor act; 00296 act.actor = actor; 00297 act.color_handlers.push_back (color_handler); 00298 //cloud_actor_map_[id] = actor; 00299 cloud_actor_map_[id] = act; 00300 style_->setCloudActorMap (boost::make_shared<CloudActorMap> (cloud_actor_map_)); 00301 return (true); 00302 } 00303 00305 template <typename PointT> bool 00306 pcl_visualization::PCLVisualizer::addPointCloud (const pcl::PointCloud<PointT> &cloud, 00307 const GeometryHandlerConstPtr &geometry_handler, 00308 const ColorHandlerConstPtr &color_handler, 00309 const std::string &id, int viewport) 00310 { 00311 if (!color_handler->isCapable ()) 00312 { 00313 pcl::console::print_warn ("[addPointCloud] A PointCloud with id <%s> requested with an invalid handler (%s)!\n", id.c_str (), color_handler->getName ().c_str ()); 00314 return (false); 00315 } 00316 00317 // Convert the PointCloud to VTK PolyData 00318 if (!geometry_handler->isCapable ()) 00319 { 00320 pcl::console::print_warn ("[addPointCloud] A PointCloud with id <%s> requested with an invalid handler (%s)!\n", id.c_str (), geometry_handler->getName ().c_str ()); 00321 return (false); 00322 } 00323 00324 // Check to see if this entry already exists (has it been already added to the visualizer?) 00325 CloudActorMap::iterator am_it = cloud_actor_map_.find (id); 00326 if (am_it != cloud_actor_map_.end ()) 00327 { 00328 //pcl::console::print_warn ("[addPointCloud] A PointCloud with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); 00329 00330 // Here we're just pushing the handlers onto the queue. If needed, something fancier could 00331 // be done such as checking if a specific handler already exists, etc. 00332 cloud_actor_map_[id].geometry_handlers.push_back (geometry_handler); 00333 cloud_actor_map_[id].color_handlers.push_back (color_handler); 00334 style_->setCloudActorMap (boost::make_shared<CloudActorMap> (cloud_actor_map_)); 00335 00336 return (true); 00337 } 00338 vtkSmartPointer<vtkPolyData> polydata; 00339 00340 convertPointCloudToVTKPolyData (geometry_handler, polydata); 00341 polydata->Update (); 00342 00343 // Get the colors from the handler 00344 vtkSmartPointer<vtkDataArray> scalars; 00345 color_handler->getColor (scalars); 00346 polydata->GetPointData ()->SetScalars (scalars); 00347 00348 // Create an Actor 00349 vtkSmartPointer<vtkLODActor> actor; 00350 createActorFromVTKDataSet (polydata, actor); 00351 00352 // Add it to all renderers 00353 addActorToRenderer (actor, viewport); 00354 00355 // Save the pointer/ID pair to the global actor map 00356 CloudActor act; 00357 act.actor = actor; 00358 act.geometry_handlers.push_back (geometry_handler); 00359 act.color_handlers.push_back (color_handler); 00360 //cloud_actor_map_[id] = actor; 00361 cloud_actor_map_[id] = act; 00362 style_->setCloudActorMap (boost::make_shared<CloudActorMap> (cloud_actor_map_)); 00363 return (true); 00364 } 00365 00367 template <typename PointT> bool 00368 pcl_visualization::PCLVisualizer::addPointCloud (const pcl::PointCloud<PointT> &cloud, 00369 const PointCloudColorHandler<PointT> &color_handler, 00370 const PointCloudGeometryHandler<PointT> &geometry_handler, 00371 const std::string &id, int viewport) 00372 { 00373 if (!color_handler.isCapable ()) 00374 { 00375 pcl::console::print_warn ("[addPointCloud] A PointCloud with id <%s> requested with an invalid handler (%s)!\n", id.c_str (), color_handler.getName ().c_str ()); 00376 return (false); 00377 } 00378 00379 if (!geometry_handler.isCapable ()) 00380 { 00381 pcl::console::print_warn ("[addPointCloud] A PointCloud with id <%s> requested with an invalid handler (%s)!\n", id.c_str (), geometry_handler.getName ().c_str ()); 00382 return (false); 00383 } 00384 00385 // Check to see if this ID entry already exists (has it been already added to the visualizer?) 00386 CloudActorMap::iterator am_it = cloud_actor_map_.find (id); 00387 00388 if (am_it != cloud_actor_map_.end ()) 00389 { 00390 pcl::console::print_warn ("[addPointCloud] A PointCloud with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); 00391 // Here we're just pushing the handlers onto the queue. If needed, something fancier could 00392 // be done such as checking if a specific handler already exists, etc. 00393 //cloud_actor_map_[id].geometry_handlers.push_back (geometry_handler); 00394 //cloud_actor_map_[id].color_handlers.push_back (color_handler); 00395 //style_->setCloudActorMap (boost::make_shared<CloudActorMap> (cloud_actor_map_)); 00396 return (false); 00397 } 00398 vtkSmartPointer<vtkPolyData> polydata; 00399 00400 // Convert the PointCloud to VTK PolyData 00401 convertPointCloudToVTKPolyData<PointT> (geometry_handler, polydata); // use the given geometry handler 00402 polydata->Update (); 00403 00404 // Get the colors from the handler 00405 vtkSmartPointer<vtkDataArray> scalars; 00406 color_handler.getColor (scalars); 00407 polydata->GetPointData ()->SetScalars (scalars); 00408 00409 // Create an Actor 00410 vtkSmartPointer<vtkLODActor> actor; 00411 createActorFromVTKDataSet (polydata, actor); 00412 00413 // Add it to all renderers 00414 addActorToRenderer (actor, viewport); 00415 00416 // Save the pointer/ID pair to the global actor map 00417 CloudActor act; 00418 act.actor = actor; 00419 //cloud_actor_map_[id] = actor; 00420 cloud_actor_map_[id] = act; 00421 style_->setCloudActorMap (boost::make_shared<CloudActorMap> (cloud_actor_map_)); 00422 return (true); 00423 } 00424 00426 template <typename PointT> void 00427 pcl_visualization::PCLVisualizer::convertPointCloudToVTKPolyData (const pcl::PointCloud<PointT> &cloud, vtkSmartPointer<vtkPolyData> &polydata) 00428 { 00429 if (!polydata) 00430 polydata = vtkSmartPointer<vtkPolyData>::New (); 00431 00432 // Create the supporting structures 00433 vtkSmartPointer<vtkCellArray> vertices = vtkSmartPointer<vtkCellArray>::New (); 00434 vtkSmartPointer<vtkPoints> points = vtkSmartPointer<vtkPoints>::New (); 00435 00436 // Set the points 00437 points->SetDataTypeToFloat (); 00438 points->SetNumberOfPoints (cloud.points.size ()); 00439 // 00440 double p[3]; 00441 for (vtkIdType i = 0; i < (int)cloud.points.size (); ++i) 00442 { 00443 p[0] = cloud.points[i].x; 00444 p[1] = cloud.points[i].y; 00445 p[2] = cloud.points[i].z; 00446 points->SetPoint (i, p); 00447 vertices->InsertNextCell ((vtkIdType)1, &i); 00448 } 00449 polydata->SetPoints (points); 00450 polydata->SetVerts (vertices); 00451 } 00452 00454 template <typename PointT> void 00455 pcl_visualization::PCLVisualizer::convertPointCloudToVTKPolyData (const pcl_visualization::PointCloudGeometryHandler<PointT> &geometry_handler, vtkSmartPointer<vtkPolyData> &polydata) 00456 { 00457 if (!polydata) 00458 polydata = vtkSmartPointer<vtkPolyData>::New (); 00459 00460 // Create the supporting structures 00461 vtkSmartPointer<vtkCellArray> vertices = vtkSmartPointer<vtkCellArray>::New (); 00462 00463 // Use the handler to obtain the geometry 00464 vtkSmartPointer<vtkPoints> points; 00465 geometry_handler.getGeometry (points); 00466 00467 // Set the vertices 00468 for (vtkIdType i = 0; i < (int)points->GetNumberOfPoints (); ++i) 00469 vertices->InsertNextCell ((vtkIdType)1, &i); 00470 polydata->SetPoints (points); 00471 polydata->SetVerts (vertices); 00472 } 00473 00475 template <typename PointT> bool 00476 pcl_visualization::PCLVisualizer::addPolygon (const pcl::PointCloud<PointT> &cloud, const std::string &id, int viewport) 00477 { 00478 // Check to see if this ID entry already exists (has it been already added to the visualizer?) 00479 ShapeActorMap::iterator am_it = shape_actor_map_.find (id); 00480 if (am_it != shape_actor_map_.end ()) 00481 { 00482 pcl::console::print_warn ("[addPolygon] A shape with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); 00483 return (false); 00484 } 00485 00486 vtkSmartPointer<vtkDataSet> data = createPolygon (cloud); 00487 00488 // Create an Actor 00489 vtkSmartPointer<vtkLODActor> actor; 00490 createActorFromVTKDataSet (data, actor); 00491 actor->GetProperty ()->SetRepresentationToWireframe (); 00492 addActorToRenderer (actor, viewport); 00493 00494 // Save the pointer/ID pair to the global actor map 00495 shape_actor_map_[id] = actor; 00496 return (true); 00497 } 00498 00500 template <typename PointT> bool 00501 pcl_visualization::PCLVisualizer::addPolygon (const pcl::PointCloud<PointT> &cloud, double r, double g, double b, const std::string &id, int viewport) 00502 { 00503 if (!addPolygon (cloud, id, viewport)) 00504 return (false); 00505 00506 ShapeActorMap::iterator am_it = shape_actor_map_.find (id); 00507 vtkLODActor* actor = vtkLODActor::SafeDownCast (am_it->second); 00508 actor->GetProperty ()->SetColor (r, g, b); 00509 actor->Modified (); 00510 return (true); 00511 } 00512 00514 template <typename P1, typename P2> bool 00515 pcl_visualization::PCLVisualizer::addLine (const P1 &pt1, const P2 &pt2, const std::string &id, int viewport) 00516 { 00517 // Check to see if this ID entry already exists (has it been already added to the visualizer?) 00518 ShapeActorMap::iterator am_it = shape_actor_map_.find (id); 00519 if (am_it != shape_actor_map_.end ()) 00520 { 00521 pcl::console::print_warn ("[addLine] A shape with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); 00522 return (false); 00523 } 00524 00525 vtkSmartPointer<vtkDataSet> data = createLine<P1, P2> (pt1, pt2); 00526 00527 // Create an Actor 00528 vtkSmartPointer<vtkLODActor> actor; 00529 createActorFromVTKDataSet (data, actor); 00530 actor->GetProperty ()->SetRepresentationToWireframe (); 00531 addActorToRenderer (actor, viewport); 00532 00533 // Save the pointer/ID pair to the global actor map 00534 shape_actor_map_[id] = actor; 00535 return (true); 00536 } 00537 00539 template <typename P1, typename P2> bool 00540 pcl_visualization::PCLVisualizer::addLine (const P1 &pt1, const P2 &pt2, double r, double g, double b, const std::string &id, int viewport) 00541 { 00542 if (!addLine (pt1, pt2, id, viewport)) 00543 return (false); 00544 00545 ShapeActorMap::iterator am_it = shape_actor_map_.find (id); 00546 vtkLODActor* actor = vtkLODActor::SafeDownCast (am_it->second); 00547 actor->GetProperty ()->SetColor (r, g, b); 00548 actor->Modified (); 00549 return (true); 00550 } 00551 00553 /*template <typename P1, typename P2> bool 00554 pcl_visualization::PCLVisualizer::addLineToGroup (const P1 &pt1, const P2 &pt2, const std::string &group_id, int viewport) 00555 { 00556 vtkSmartPointer<vtkDataSet> data = createLine<P1, P2> (pt1, pt2); 00557 00558 // Check to see if this ID entry already exists (has it been already added to the visualizer?) 00559 ShapeActorMap::iterator am_it = shape_actor_map_.find (group_id); 00560 if (am_it != shape_actor_map_.end ()) 00561 { 00562 // Get the old data 00563 vtkPolyDataMapper* mapper = static_cast<vtkPolyDataMapper*>(am_it->second->GetMapper ()); 00564 vtkPolyData* olddata = static_cast<vtkPolyData*>(mapper->GetInput ()); 00565 // Add it to the current data 00566 vtkSmartPointer<vtkAppendPolyData> alldata = vtkSmartPointer<vtkAppendPolyData>::New (); 00567 alldata->AddInput (olddata); 00568 00569 // Convert to vtkPolyData 00570 vtkSmartPointer<vtkPolyData> curdata = (vtkPolyData::SafeDownCast (data)); 00571 alldata->AddInput (curdata); 00572 00573 mapper->SetInput (alldata->GetOutput ()); 00574 00575 am_it->second->SetMapper (mapper); 00576 am_it->second->Modified (); 00577 return (true); 00578 } 00579 00580 // Create an Actor 00581 vtkSmartPointer<vtkLODActor> actor; 00582 createActorFromVTKDataSet (data, actor); 00583 actor->GetProperty ()->SetRepresentationToWireframe (); 00584 actor->GetProperty ()->SetColor (1, 0, 0); 00585 addActorToRenderer (actor, viewport); 00586 00587 // Save the pointer/ID pair to the global actor map 00588 shape_actor_map_[group_id] = actor; 00589 00590 //ShapeActorMap::iterator am_it = shape_actor_map_.find (id); 00591 //vtkSmartPointer<vtkLODActor> actor = am_it->second; 00592 //actor->GetProperty ()->SetColor (r, g, b); 00593 //actor->Modified (); 00594 return (true); 00595 }*/ 00596 00598 template <typename PointT> bool 00599 pcl_visualization::PCLVisualizer::addSphere (const PointT ¢er, double radius, const std::string &id, int viewport) 00600 { 00601 // Check to see if this ID entry already exists (has it been already added to the visualizer?) 00602 ShapeActorMap::iterator am_it = shape_actor_map_.find (id); 00603 if (am_it != shape_actor_map_.end ()) 00604 { 00605 pcl::console::print_warn ("[addSphere] A shape with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); 00606 return (false); 00607 } 00608 00609 vtkSmartPointer<vtkDataSet> data = createSphere<PointT> (center, radius); 00610 00611 // Create an Actor 00612 vtkSmartPointer<vtkLODActor> actor; 00613 createActorFromVTKDataSet (data, actor); 00614 actor->GetProperty ()->SetRepresentationToWireframe (); 00615 addActorToRenderer (actor, viewport); 00616 00617 // Save the pointer/ID pair to the global actor map 00618 shape_actor_map_[id] = actor; 00619 return (true); 00620 } 00621 00623 template <typename PointT> bool 00624 pcl_visualization::PCLVisualizer::addSphere (const PointT ¢er, double radius, double r, double g, double b, const std::string &id, int viewport) 00625 { 00626 if (!addSphere (center, radius, id, viewport)) 00627 return (false); 00628 00629 ShapeActorMap::iterator am_it = shape_actor_map_.find (id); 00630 vtkLODActor* actor = vtkLODActor::SafeDownCast (am_it->second); 00631 actor->GetProperty ()->SetColor (r, g, b); 00632 actor->Modified (); 00633 return (true); 00634 } 00635 00636 template <typename PointNT> bool 00637 pcl_visualization::PCLVisualizer::addPointCloudNormals (const pcl::PointCloud<PointNT> &cloud, 00638 int level, double scale, const std::string &id, int viewport) 00639 { 00640 return addPointCloudNormals<PointNT, PointNT>(cloud, cloud, level, scale, id, viewport); 00641 } 00642 00644 template <typename PointT, typename PointNT> bool 00645 pcl_visualization::PCLVisualizer::addPointCloudNormals (const pcl::PointCloud<PointT> &cloud, 00646 const pcl::PointCloud<PointNT> &normals, 00647 int level, double scale, 00648 const std::string &id, int viewport) 00649 { 00650 if (normals.points.size () != cloud.points.size ()) 00651 { 00652 pcl::console::print_error ("[addPointCloudNormals] The number of points differs from the number of normals!\n"); 00653 return (false); 00654 } 00655 // Check to see if this ID entry already exists (has it been already added to the visualizer?) 00656 CloudActorMap::iterator am_it = cloud_actor_map_.find (id); 00657 00658 if (am_it != cloud_actor_map_.end ()) 00659 { 00660 pcl::console::print_warn ("[addPointCloudNormals] A PointCloud with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); 00661 return (false); 00662 } 00663 00664 vtkSmartPointer<vtkAppendPolyData> polydata = vtkSmartPointer<vtkAppendPolyData>::New (); 00665 00666 for (size_t i = 0; i < cloud.points.size (); i+=level) 00667 { 00668 PointT p = cloud.points[i]; 00669 p.x += normals.points[i].normal[0] * scale; p.y += normals.points[i].normal[1] * scale; p.z += normals.points[i].normal[2] * scale; 00670 vtkSmartPointer<vtkLineSource> line = vtkSmartPointer<vtkLineSource>::New (); 00671 line->SetPoint1 (cloud.points[i].x, cloud.points[i].y, cloud.points[i].z); 00672 line->SetPoint2 (p.x, p.y, p.z); 00673 line->Update (); 00674 polydata->AddInput (line->GetOutput ()); 00675 } 00676 // Convert the PointCloud to VTK PolyData 00677 polydata->Update (); 00678 00679 // Create an Actor 00680 vtkSmartPointer<vtkLODActor> actor; 00681 createActorFromVTKDataSet (polydata->GetOutput (), actor); 00682 00683 // Add it to all renderers 00684 addActorToRenderer (actor, viewport); 00685 00686 // Save the pointer/ID pair to the global actor map 00687 CloudActor act; 00688 //act.color_handlers.push_back (handler); 00689 act.actor = actor; 00690 cloud_actor_map_[id] = act; 00691 //style_->setCloudActorMap (boost::make_shared<CloudActorMap> (cloud_actor_map_)); 00692 return (true); 00693 }