00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <pcl/common/common_headers.h>
00039 #include <pcl_visualization/common/common.h>
00040 #include <pcl_visualization/pcl_visualizer.h>
00041 #include <vtkTextActor.h>
00042 #include <vtkTextProperty.h>
00043 #include <vtkCellData.h>
00044
00046 pcl_visualization::PCLVisualizer::PCLVisualizer (const std::string &name) :
00047 rens_ (vtkSmartPointer<vtkRendererCollection>::New ()),
00048 style_ (vtkSmartPointer<pcl_visualization::PCLVisualizerInteractorStyle>::New ())
00049 {
00050
00051 vtkSmartPointer<vtkTextActor> txt = vtkSmartPointer<vtkTextActor>::New ();
00052 vtkSmartPointer<FPSCallback> update_fps = vtkSmartPointer<FPSCallback>::New ();
00053 update_fps->setTextActor (txt);
00054
00055
00056 vtkSmartPointer<vtkRenderer> ren = vtkSmartPointer<vtkRenderer>::New ();
00057 ren->AddObserver (vtkCommand::EndEvent, update_fps);
00058 ren->AddActor (txt);
00059
00060 rens_->AddItem (ren);
00061
00062
00063 win_ = vtkSmartPointer<vtkRenderWindow>::New ();
00064 win_->SetWindowName (name.c_str ());
00065 win_->SetStereoTypeToAnaglyph ();
00066
00067
00068 int *scr_size = win_->GetScreenSize ();
00069
00070 win_->SetSize (scr_size[0] / 2, scr_size[1] / 2);
00071
00072
00073 rens_->InitTraversal ();
00074 vtkRenderer* renderer = NULL;
00075 while ((renderer = rens_->GetNextItem ()) != NULL)
00076 win_->AddRenderer (renderer);
00077
00078
00079 style_->Initialize ();
00080 style_->setRendererCollection (rens_);
00081 style_->setCloudActorMap (boost::make_shared<CloudActorMap> (cloud_actor_map_));
00082 style_->UseTimersOn ();
00083
00084
00085
00086 interactor_ = vtkSmartPointer<PCLVisualizerInteractor>::New ();
00087
00088 interactor_->SetRenderWindow (win_);
00089 interactor_->SetInteractorStyle (style_);
00090 interactor_->SetDesiredUpdateRate (30.0);
00091
00092 interactor_->Initialize ();
00093 interactor_->CreateRepeatingTimer (5000L);
00094
00095 exit_main_loop_timer_callback_ = vtkSmartPointer<ExitMainLoopTimerCallback>::New ();
00096 exit_main_loop_timer_callback_->pcl_visualizer = this;
00097 exit_main_loop_timer_callback_->right_timer_id = -1;
00098 interactor_->AddObserver (vtkCommand::TimerEvent, exit_main_loop_timer_callback_);
00099
00100 exit_callback_ = vtkSmartPointer<ExitCallback>::New ();
00101 exit_callback_->pcl_visualizer = this;
00102 interactor_->AddObserver (vtkCommand::ExitEvent, exit_callback_);
00103
00104 resetStoppedFlag ();
00105 }
00106
00108 pcl_visualization::PCLVisualizer::PCLVisualizer (int &argc, char **argv, const std::string &name, PCLVisualizerInteractorStyle* style) :
00109 rens_ (vtkSmartPointer<vtkRendererCollection>::New ())
00110 {
00111 style_ = style;
00112
00113
00114 vtkSmartPointer<vtkTextActor> txt = vtkSmartPointer<vtkTextActor>::New ();
00115 vtkSmartPointer<FPSCallback> update_fps = vtkSmartPointer<FPSCallback>::New ();
00116 update_fps->setTextActor (txt);
00117
00118
00119 vtkSmartPointer<vtkRenderer> ren = vtkSmartPointer<vtkRenderer>::New ();
00120 ren->AddObserver (vtkCommand::EndEvent, update_fps);
00121 ren->AddActor (txt);
00122
00123 rens_->AddItem (ren);
00124
00125
00126 win_ = vtkSmartPointer<vtkRenderWindow>::New ();
00127 win_->SetWindowName (name.c_str ());
00128 win_->SetStereoTypeToAnaglyph ();
00129
00130
00131 int *scr_size = win_->GetScreenSize ();
00132 camera_.window_size[0] = scr_size[0]; camera_.window_size[1] = scr_size[1] / 2;
00133 camera_.window_pos[0] = camera_.window_pos[1] = 0;
00134
00135
00136 initCameraParameters ();
00137
00138
00139 getCameraParameters (argc, argv);
00140 updateCamera ();
00141
00142 win_->SetSize (camera_.window_size[0], camera_.window_size[1]);
00143 win_->SetPosition (camera_.window_pos[0], camera_.window_pos[1]);
00144
00145
00146 rens_->InitTraversal ();
00147 vtkRenderer* renderer = NULL;
00148 while ((renderer = rens_->GetNextItem ()) != NULL)
00149 win_->AddRenderer (renderer);
00150
00151
00152 style_->Initialize ();
00153 style_->setRendererCollection (rens_);
00154 style_->setCloudActorMap (boost::make_shared<CloudActorMap> (cloud_actor_map_));
00155 style_->UseTimersOn ();
00156
00157
00158
00159 interactor_ = vtkSmartPointer<PCLVisualizerInteractor>::New ();
00160
00161 interactor_->SetRenderWindow (win_);
00162 interactor_->SetInteractorStyle (style_);
00163 interactor_->SetDesiredUpdateRate (30.0);
00164
00165 interactor_->Initialize ();
00166 interactor_->CreateRepeatingTimer (5000L);
00167
00168 exit_main_loop_timer_callback_ = vtkSmartPointer<ExitMainLoopTimerCallback>::New();
00169 exit_main_loop_timer_callback_->pcl_visualizer = this;
00170 exit_main_loop_timer_callback_->right_timer_id = -1;
00171 interactor_->AddObserver(vtkCommand::TimerEvent, exit_main_loop_timer_callback_);
00172
00173 exit_callback_ = vtkSmartPointer<ExitCallback>::New();
00174 exit_callback_->pcl_visualizer = this;
00175 interactor_->AddObserver(vtkCommand::ExitEvent, exit_callback_);
00176
00177 resetStoppedFlag ();
00178 }
00179
00181 pcl_visualization::PCLVisualizer::~PCLVisualizer ()
00182 {
00183
00184 rens_->RemoveAllItems ();
00185 }
00186
00188 void
00189 pcl_visualization::PCLVisualizer::spin ()
00190 {
00191 resetStoppedFlag ();
00192
00193 win_->Render();
00194 interactor_->Start ();
00195 }
00196
00198 void
00199 pcl_visualization::PCLVisualizer::spinOnce (int time, bool force_redraw)
00200 {
00201 resetStoppedFlag ();
00202
00203 if (time <= 0)
00204 time = 1;
00205
00206 if (force_redraw)
00207 {
00208 interactor_->Render();
00209 exit_main_loop_timer_callback_->right_timer_id = interactor_->CreateRepeatingTimer(time);
00210 interactor_->Start();
00211 interactor_->DestroyTimer(exit_main_loop_timer_callback_->right_timer_id);
00212 return;
00213 }
00214
00215 DO_EVERY(1.0/interactor_->GetDesiredUpdateRate(),
00216 interactor_->Render();
00217 exit_main_loop_timer_callback_->right_timer_id = interactor_->CreateRepeatingTimer(time);
00218 interactor_->Start();
00219 interactor_->DestroyTimer(exit_main_loop_timer_callback_->right_timer_id);
00220 );
00221 }
00222
00224 void
00225 pcl_visualization::PCLVisualizer::addCoordinateSystem (double scale, int viewport)
00226 {
00227 vtkSmartPointer<vtkAxes> axes = vtkSmartPointer<vtkAxes>::New ();
00228 axes->SetOrigin (0, 0, 0);
00229 axes->SetScaleFactor (scale);
00230
00231 vtkSmartPointer<vtkFloatArray> axes_colors = vtkSmartPointer<vtkFloatArray>::New ();
00232 axes_colors->Allocate (6);
00233 axes_colors->InsertNextValue (0.0);
00234 axes_colors->InsertNextValue (0.0);
00235 axes_colors->InsertNextValue (0.5);
00236 axes_colors->InsertNextValue (0.5);
00237 axes_colors->InsertNextValue (1.0);
00238 axes_colors->InsertNextValue (1.0);
00239
00240 vtkSmartPointer<vtkPolyData> axes_data = axes->GetOutput ();
00241 axes_data->Update ();
00242 axes_data->GetPointData ()->SetScalars (axes_colors);
00243
00244 vtkSmartPointer<vtkTubeFilter> axes_tubes = vtkSmartPointer<vtkTubeFilter>::New ();
00245 axes_tubes->SetInput (axes_data);
00246 axes_tubes->SetRadius (axes->GetScaleFactor () / 50.0);
00247 axes_tubes->SetNumberOfSides (6);
00248
00249 vtkSmartPointer<vtkPolyDataMapper> axes_mapper = vtkSmartPointer<vtkPolyDataMapper>::New ();
00250 axes_mapper->SetScalarModeToUsePointData ();
00251 axes_mapper->SetInput (axes_tubes->GetOutput ());
00252
00253 vtkSmartPointer<vtkLODActor> axes_actor = vtkSmartPointer<vtkLODActor>::New ();
00254 axes_actor->SetMapper (axes_mapper);
00255
00256 addActorToRenderer (axes_actor, viewport);
00257 }
00258
00260 void
00261 pcl_visualization::PCLVisualizer::addCoordinateSystem (double scale, float x, float y, float z, int viewport)
00262 {
00263 vtkSmartPointer<vtkAxes> axes = vtkSmartPointer<vtkAxes>::New ();
00264 axes->SetOrigin (0, 0, 0);
00265 axes->SetScaleFactor (scale);
00266
00267 vtkSmartPointer<vtkFloatArray> axes_colors = vtkSmartPointer<vtkFloatArray>::New ();
00268 axes_colors->Allocate (6);
00269 axes_colors->InsertNextValue (0.0);
00270 axes_colors->InsertNextValue (0.0);
00271 axes_colors->InsertNextValue (0.5);
00272 axes_colors->InsertNextValue (0.5);
00273 axes_colors->InsertNextValue (1.0);
00274 axes_colors->InsertNextValue (1.0);
00275
00276 vtkSmartPointer<vtkPolyData> axes_data = axes->GetOutput ();
00277 axes_data->Update ();
00278 axes_data->GetPointData ()->SetScalars (axes_colors);
00279
00280 vtkSmartPointer<vtkTubeFilter> axes_tubes = vtkSmartPointer<vtkTubeFilter>::New ();
00281 axes_tubes->SetInput (axes_data);
00282 axes_tubes->SetRadius (axes->GetScaleFactor () / 50.0);
00283 axes_tubes->SetNumberOfSides (6);
00284
00285 vtkSmartPointer<vtkPolyDataMapper> axes_mapper = vtkSmartPointer<vtkPolyDataMapper>::New ();
00286 axes_mapper->SetScalarModeToUsePointData ();
00287 axes_mapper->SetInput (axes_tubes->GetOutput ());
00288
00289 vtkSmartPointer<vtkLODActor> axes_actor = vtkSmartPointer<vtkLODActor>::New ();
00290 axes_actor->SetMapper (axes_mapper);
00291 axes_actor->SetPosition (x, y, z);
00292
00293 addActorToRenderer (axes_actor, viewport);
00294 }
00295
00297 void
00298 pcl_visualization::PCLVisualizer::removeCoordinateSystem (int viewport)
00299 {
00300
00301
00302
00303
00304
00305
00306
00307
00308
00309
00310
00311
00312
00313
00314
00315
00316
00317
00318
00319
00320
00321
00322
00323
00324
00325
00326
00327
00328
00329
00330 }
00331
00333 bool
00334 pcl_visualization::PCLVisualizer::removePointCloud (const std::string &id, int viewport)
00335 {
00336
00337 CloudActorMap::iterator am_it = cloud_actor_map_.find (id);
00338
00339 if (am_it == cloud_actor_map_.end ())
00340 {
00341
00342 return (false);
00343 }
00344
00345
00346 CloudActor act = am_it->second;
00347 vtkSmartPointer<vtkLODActor> actor = act.actor;
00348 am_it->second.geometry_handlers.clear ();
00349 am_it->second.color_handlers.clear ();
00350
00351
00352
00353 removeActorFromRenderer (actor, viewport);
00354
00355
00356 cloud_actor_map_.erase (am_it);
00357 style_->setCloudActorMap (boost::make_shared<CloudActorMap> (cloud_actor_map_));
00358 return (true);
00359 }
00360
00362 bool
00363 pcl_visualization::PCLVisualizer::removeShape (const std::string &id, int viewport)
00364 {
00365
00366 ShapeActorMap::iterator am_it = shape_actor_map_.find (id);
00367
00368 if (am_it == shape_actor_map_.end ())
00369 {
00370
00371 return (false);
00372 }
00373
00374
00375 removeActorFromRenderer (am_it->second, viewport);
00376
00377
00378 shape_actor_map_.erase (am_it);
00379 return (true);
00380 }
00381
00383 bool
00384 pcl_visualization::PCLVisualizer::addPointCloudPrincipalCurvatures (const pcl::PointCloud<pcl::PointXYZ> &cloud,
00385 const pcl::PointCloud<pcl::Normal> &normals,
00386 const pcl::PointCloud<pcl::PrincipalCurvatures> &pcs,
00387 int level, double scale,
00388 const std::string &id, int viewport)
00389 {
00390 if (pcs.points.size () != cloud.points.size () || normals.points.size () != cloud.points.size ())
00391 {
00392 terminal_tools::print_error ("[addPointCloudPrincipalCurvatures] The number of points differs from the number of principal curvatures/normals!\n");
00393 return (false);
00394 }
00395
00396 CloudActorMap::iterator am_it = cloud_actor_map_.find (id);
00397
00398 if (am_it != cloud_actor_map_.end ())
00399 {
00400 terminal_tools::print_warn ("[addPointCloudPrincipalCurvatures] A PointCloud with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ());
00401 return (false);
00402 }
00403
00404 vtkSmartPointer<vtkAppendPolyData> polydata_1 = vtkSmartPointer<vtkAppendPolyData>::New ();
00405 vtkSmartPointer<vtkAppendPolyData> polydata_2 = vtkSmartPointer<vtkAppendPolyData>::New ();
00406
00407
00408 unsigned char green[3] = {0, 255, 0};
00409 unsigned char blue[3] = {0, 0, 255};
00410
00411
00412 vtkSmartPointer<vtkUnsignedCharArray> line_1_colors =vtkSmartPointer<vtkUnsignedCharArray>::New ();
00413 line_1_colors->SetNumberOfComponents (3);
00414 line_1_colors->SetName ("Colors");
00415 vtkSmartPointer<vtkUnsignedCharArray> line_2_colors =vtkSmartPointer<vtkUnsignedCharArray>::New ();
00416 line_2_colors->SetNumberOfComponents (3);
00417 line_2_colors->SetName ("Colors");
00418
00419
00420 for (size_t i = 0; i < cloud.points.size (); i+=level)
00421 {
00422 pcl::PointXYZ p = cloud.points[i];
00423 p.x += (pcs.points[i].pc1 * pcs.points[i].principal_curvature[0]) * scale;
00424 p.y += (pcs.points[i].pc1 * pcs.points[i].principal_curvature[1]) * scale;
00425 p.z += (pcs.points[i].pc1 * pcs.points[i].principal_curvature[2]) * scale;
00426
00427 vtkSmartPointer<vtkLineSource> line_1 = vtkSmartPointer<vtkLineSource>::New ();
00428 line_1->SetPoint1 (cloud.points[i].x, cloud.points[i].y, cloud.points[i].z);
00429 line_1->SetPoint2 (p.x, p.y, p.z);
00430 line_1->Update ();
00431 polydata_1->AddInput (line_1->GetOutput ());
00432 line_1_colors->InsertNextTupleValue (green);
00433 }
00434 polydata_1->Update ();
00435 vtkSmartPointer<vtkPolyData> line_1_data = polydata_1->GetOutput ();
00436 line_1_data->GetCellData ()->SetScalars (line_1_colors);
00437
00438
00439 for (size_t i = 0; i < cloud.points.size (); i+=level)
00440 {
00441 Eigen::Vector3f pc (pcs.points[i].principal_curvature[0], pcs.points[i].principal_curvature[1], pcs.points[i].principal_curvature[2]);
00442 Eigen::Vector3f normal (normals.points[i].normal[0], normals.points[i].normal[1], normals.points[i].normal[2]);
00443 Eigen::Vector3f pc_c = pc.cross (normal);
00444
00445 pcl::PointXYZ p = cloud.points[i];
00446 p.x += (pcs.points[i].pc2 * pc_c[0]) * scale;
00447 p.y += (pcs.points[i].pc2 * pc_c[1]) * scale;
00448 p.z += (pcs.points[i].pc2 * pc_c[2]) * scale;
00449
00450 vtkSmartPointer<vtkLineSource> line_2 = vtkSmartPointer<vtkLineSource>::New ();
00451 line_2->SetPoint1 (cloud.points[i].x, cloud.points[i].y, cloud.points[i].z);
00452 line_2->SetPoint2 (p.x, p.y, p.z);
00453 line_2->Update ();
00454 polydata_2->AddInput (line_2->GetOutput ());
00455 line_2_colors->InsertNextTupleValue (blue);
00456 }
00457 polydata_2->Update ();
00458 vtkSmartPointer<vtkPolyData> line_2_data = polydata_2->GetOutput ();
00459 line_2_data->GetCellData ()->SetScalars (line_2_colors);
00460
00461
00462 vtkSmartPointer<vtkAppendPolyData> alldata = vtkSmartPointer<vtkAppendPolyData>::New ();
00463 alldata->AddInput (line_1_data);
00464 alldata->AddInput (line_2_data);
00465
00466
00467 vtkSmartPointer<vtkLODActor> actor;
00468 createActorFromVTKDataSet (alldata->GetOutput (), actor);
00469 actor->GetMapper ()->SetScalarModeToUseCellData ();
00470
00471
00472 addActorToRenderer (actor, viewport);
00473
00474
00475 CloudActor act;
00476
00477 act.actor = actor;
00478 cloud_actor_map_[id] = act;
00479
00480 return (true);
00481 }
00482
00484 bool
00485 pcl_visualization::PCLVisualizer::addPointCloud (const pcl::PointCloud<pcl::PointXYZ> &cloud,
00486 const std::string &id, int viewport)
00487 {
00488
00489 CloudActorMap::iterator am_it = cloud_actor_map_.find (id);
00490
00491 if (am_it != cloud_actor_map_.end ())
00492 {
00493 terminal_tools::print_warn ("[addPointCloud] A PointCloud with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ());
00494 return (false);
00495 }
00496 vtkSmartPointer<vtkPolyData> polydata;
00497
00498
00499 convertPointCloudToVTKPolyData (cloud, polydata);
00500 polydata->Update ();
00501
00502
00503 vtkSmartPointer<vtkDataArray> scalars;
00504 PointCloudColorHandlerRandom<pcl::PointXYZ> handler (cloud);
00505 handler.getColor (scalars);
00506 polydata->GetPointData ()->SetScalars (scalars);
00507
00508
00509 vtkSmartPointer<vtkLODActor> actor;
00510 createActorFromVTKDataSet (polydata, actor);
00511
00512
00513 addActorToRenderer (actor, viewport);
00514
00515
00516 CloudActor act;
00517
00518 act.actor = actor;
00519 cloud_actor_map_[id] = act;
00520
00521 style_->setCloudActorMap (boost::make_shared<CloudActorMap> (cloud_actor_map_));
00522 return (true);
00523 }
00524
00526 void
00527 pcl_visualization::PCLVisualizer::removeActorFromRenderer (const vtkSmartPointer<vtkLODActor> &actor, int viewport)
00528 {
00529
00530 rens_->InitTraversal ();
00531 vtkRenderer* renderer = NULL;
00532 int i = 1;
00533 while ((renderer = rens_->GetNextItem ()) != NULL)
00534 {
00535
00536 if (viewport == 0)
00537 {
00538 renderer->RemoveActor (actor);
00539 renderer->Render ();
00540 }
00541 else if (viewport == i)
00542 {
00543 renderer->RemoveActor (actor);
00544 renderer->Render ();
00545 }
00546 ++i;
00547 }
00548 }
00549
00551 void
00552 pcl_visualization::PCLVisualizer::addActorToRenderer (const vtkSmartPointer<vtkProp> &actor, int viewport)
00553 {
00554
00555 rens_->InitTraversal ();
00556 vtkRenderer* renderer = NULL;
00557 int i = 1;
00558 while ((renderer = rens_->GetNextItem ()) != NULL)
00559 {
00560
00561 if (viewport == 0)
00562 {
00563 renderer->AddActor (actor);
00564 renderer->Render ();
00565 }
00566 else if (viewport == i)
00567 {
00568 renderer->AddActor (actor);
00569 renderer->Render ();
00570 }
00571 ++i;
00572 }
00573 }
00574
00576 void
00577 pcl_visualization::PCLVisualizer::removeActorFromRenderer (const vtkSmartPointer<vtkProp> &actor, int viewport)
00578 {
00579
00580 rens_->InitTraversal ();
00581 vtkRenderer* renderer = NULL;
00582 int i = 1;
00583 while ((renderer = rens_->GetNextItem ()) != NULL)
00584 {
00585
00586 if (viewport == 0)
00587 {
00588 renderer->RemoveActor (actor);
00589 renderer->Render ();
00590 }
00591 else if (viewport == i)
00592 {
00593 renderer->RemoveActor (actor);
00594 renderer->Render ();
00595 }
00596 ++i;
00597 }
00598 }
00599
00601 void
00602 pcl_visualization::PCLVisualizer::createActorFromVTKDataSet (const vtkSmartPointer<vtkDataSet> &data,
00603 vtkSmartPointer<vtkLODActor> &actor)
00604 {
00605
00606 if (!actor)
00607 actor = vtkSmartPointer<vtkLODActor>::New ();
00608
00609 vtkSmartPointer<vtkDataArray> scalars = data->GetPointData ()->GetScalars ();
00610 double minmax[2];
00611 if (scalars)
00612 scalars->GetRange (minmax);
00613
00614 vtkSmartPointer<vtkDataSetMapper> mapper = vtkSmartPointer<vtkDataSetMapper>::New ();
00615 mapper->SetInput (data);
00616 if (scalars)
00617 mapper->SetScalarRange (minmax);
00618 mapper->SetScalarModeToUsePointData ();
00619 mapper->ScalarVisibilityOn ();
00620
00621 actor->SetNumberOfCloudPoints (data->GetNumberOfPoints () / 10);
00622 actor->GetProperty ()->SetInterpolationToFlat ();
00623
00624 actor->SetMapper (mapper);
00625 }
00626
00628 void
00629 pcl_visualization::PCLVisualizer::convertPointCloudToVTKPolyData (const pcl::PointCloud<pcl::PointXYZ> &cloud,
00630 vtkSmartPointer<vtkPolyData> &polydata)
00631 {
00632 if (!polydata)
00633 polydata = vtkSmartPointer<vtkPolyData>::New ();
00634
00635
00636 vtkSmartPointer<vtkCellArray> vertices = vtkSmartPointer<vtkCellArray>::New ();
00637 vtkSmartPointer<vtkPoints> points = vtkSmartPointer<vtkPoints>::New ();
00638
00639
00640 points->SetDataTypeToFloat ();
00641 points->SetNumberOfPoints (cloud.points.size ());
00642
00643 double p[3];
00644 for (vtkIdType i = 0; i < (int)cloud.points.size (); ++i)
00645 {
00646 p[0] = cloud.points[i].x;
00647 p[1] = cloud.points[i].y;
00648 p[2] = cloud.points[i].z;
00649 points->SetPoint (i, p);
00650 vertices->InsertNextCell ((vtkIdType)1, &i);
00651 }
00652 polydata->SetPoints (points);
00653 polydata->SetVerts (vertices);
00654 }
00655
00657 void
00658 pcl_visualization::PCLVisualizer::convertPointCloudToVTKPolyData (const GeometryHandlerConstPtr &geometry_handler, vtkSmartPointer<vtkPolyData> &polydata)
00659 {
00660 if (!polydata)
00661 polydata = vtkSmartPointer<vtkPolyData>::New ();
00662
00663
00664 vtkSmartPointer<vtkCellArray> vertices = vtkSmartPointer<vtkCellArray>::New ();
00665
00666
00667 vtkSmartPointer<vtkPoints> points;
00668 geometry_handler->getGeometry (points);
00669
00670
00671 for (vtkIdType i = 0; i < (int)points->GetNumberOfPoints (); ++i)
00672 vertices->InsertNextCell ((vtkIdType)1, &i);
00673 polydata->SetPoints (points);
00674 polydata->SetVerts (vertices);
00675 }
00676
00678 void
00679 pcl_visualization::PCLVisualizer::setBackgroundColor (const double &r, const double &g, const double &b, int viewport)
00680 {
00681 rens_->InitTraversal ();
00682 vtkRenderer* renderer = NULL;
00683 int i = 1;
00684 while ((renderer = rens_->GetNextItem ()) != NULL)
00685 {
00686
00687 if (viewport == 0)
00688 {
00689 renderer->SetBackground (r, g, b);
00690 renderer->Render ();
00691 }
00692 else if (viewport == i)
00693 {
00694 renderer->SetBackground (r, g, b);
00695 renderer->Render ();
00696 }
00697 ++i;
00698 }
00699 }
00700
00702 bool
00703 pcl_visualization::PCLVisualizer::setPointCloudRenderingProperties (int property, double val1, double val2, double val3, const std::string &id, int viewport)
00704 {
00705
00706 CloudActorMap::iterator am_it = cloud_actor_map_.find (id);
00707
00708 if (am_it == cloud_actor_map_.end ())
00709 {
00710 terminal_tools::print_error ("[setPointCloudRenderingProperties] Could not find any PointCloud datasets with id <%s>!\n", id.c_str ());
00711 return (false);
00712 }
00713
00714 vtkLODActor* actor = vtkLODActor::SafeDownCast (am_it->second.actor);
00715
00716 switch (property)
00717 {
00718 case PCL_VISUALIZER_COLOR:
00719 {
00720 actor->GetProperty ()->SetColor (val1, val2, val3);
00721 actor->Modified ();
00722 break;
00723 }
00724 default:
00725 {
00726 terminal_tools::print_error ("[setPointCloudRenderingProperties] Unknown property (%d) specified!\n", property);
00727 return (false);
00728 }
00729 }
00730 return (true);
00731 }
00732
00734 bool
00735 pcl_visualization::PCLVisualizer::getPointCloudRenderingProperties (int property, double &value, const std::string &id)
00736 {
00737
00738 CloudActorMap::iterator am_it = cloud_actor_map_.find (id);
00739
00740 if (am_it == cloud_actor_map_.end ())
00741 return (false);
00742
00743 vtkLODActor* actor = vtkLODActor::SafeDownCast (am_it->second.actor);
00744
00745 switch (property)
00746 {
00747 case PCL_VISUALIZER_POINT_SIZE:
00748 {
00749 value = actor->GetProperty ()->GetPointSize ();
00750 actor->Modified ();
00751 break;
00752 }
00753 case PCL_VISUALIZER_OPACITY:
00754 {
00755 value = actor->GetProperty ()->GetOpacity ();
00756 actor->Modified ();
00757 break;
00758 }
00759 case PCL_VISUALIZER_LINE_WIDTH:
00760 {
00761 value = actor->GetProperty ()->GetLineWidth ();
00762 actor->Modified ();
00763 break;
00764 }
00765 default:
00766 {
00767 terminal_tools::print_error ("[getPointCloudRenderingProperties] Unknown property (%d) specified!\n", property);
00768 return (false);
00769 }
00770 }
00771 return (true);
00772 }
00773
00775 bool
00776 pcl_visualization::PCLVisualizer::setPointCloudRenderingProperties (int property, double value, const std::string &id, int viewport)
00777 {
00778
00779 CloudActorMap::iterator am_it = cloud_actor_map_.find (id);
00780
00781 if (am_it == cloud_actor_map_.end ())
00782 {
00783 terminal_tools::print_error ("[setPointCloudRenderingProperties] Could not find any PointCloud datasets with id <%s>!\n", id.c_str ());
00784 return (false);
00785 }
00786
00787 vtkLODActor* actor = vtkLODActor::SafeDownCast (am_it->second.actor);
00788
00789 switch (property)
00790 {
00791 case PCL_VISUALIZER_POINT_SIZE:
00792 {
00793 actor->GetProperty ()->SetPointSize (value);
00794 actor->Modified ();
00795 break;
00796 }
00797 case PCL_VISUALIZER_OPACITY:
00798 {
00799 actor->GetProperty ()->SetOpacity (value);
00800 actor->Modified ();
00801 break;
00802 }
00803 case PCL_VISUALIZER_LINE_WIDTH:
00804 {
00805 actor->GetProperty ()->SetLineWidth (value);
00806 actor->Modified ();
00807 break;
00808 }
00809 default:
00810 {
00811 terminal_tools::print_error ("[setPointCloudRenderingProperties] Unknown property (%d) specified!\n", property);
00812 return (false);
00813 }
00814 }
00815 return (true);
00816 }
00817
00819 bool
00820 pcl_visualization::PCLVisualizer::setShapeRenderingProperties (int property, double value, const std::string &id, int viewport)
00821 {
00822
00823 ShapeActorMap::iterator am_it = shape_actor_map_.find (id);
00824
00825 if (am_it == shape_actor_map_.end ())
00826 {
00827 terminal_tools::print_error ("[setShapeRenderingProperties] Could not find any shape with id <%s>!\n", id.c_str ());
00828 return (false);
00829 }
00830
00831 vtkLODActor* actor = vtkLODActor::SafeDownCast (am_it->second);
00832
00833 switch (property)
00834 {
00835 case PCL_VISUALIZER_OPACITY:
00836 {
00837 actor->GetProperty ()->SetOpacity (value);
00838 actor->Modified ();
00839 break;
00840 }
00841 case PCL_VISUALIZER_LINE_WIDTH:
00842 {
00843 actor->GetProperty ()->SetLineWidth (value);
00844 actor->Modified ();
00845 break;
00846 }
00847 case PCL_VISUALIZER_FONT_SIZE:
00848 {
00849 vtkTextActor* text_actor = vtkTextActor::SafeDownCast (am_it->second);
00850 vtkSmartPointer<vtkTextProperty> tprop = text_actor->GetTextProperty ();
00851 tprop->SetFontSize (value);
00852 text_actor->Modified ();
00853 break;
00854 }
00855 default:
00856 {
00857 terminal_tools::print_error ("[setShapeRenderingProperties] Unknown property (%d) specified!\n", property);
00858 return (false);
00859 }
00860 }
00861 return (true);
00862 }
00863
00864
00866 void
00867 pcl_visualization::PCLVisualizer::initCameraParameters ()
00868 {
00869
00870 camera_.clip[0] = 0.01; camera_.clip[1] = 1000.01;
00871 camera_.focal[0] = camera_.focal[1] = camera_.focal[2] = 0;
00872 camera_.pos[0] = camera_.pos[1] = 0; camera_.pos[2] = 1;
00873 camera_.view[0] = camera_.view[2] = 0; camera_.view[1] = 1;
00874 }
00875
00877 void
00878 pcl_visualization::PCLVisualizer::updateCamera ()
00879 {
00880
00881 rens_->InitTraversal ();
00882 vtkRenderer* renderer = NULL;
00883 while ((renderer = rens_->GetNextItem ()) != NULL)
00884 {
00885 renderer->GetActiveCamera ()->SetPosition (camera_.pos);
00886 renderer->GetActiveCamera ()->SetFocalPoint (camera_.focal);
00887 renderer->GetActiveCamera ()->SetViewUp (camera_.view);
00888 renderer->GetActiveCamera ()->SetClippingRange (camera_.clip);
00889 }
00890 }
00892 void
00893 pcl_visualization::PCLVisualizer::resetCamera ()
00894 {
00895
00896 rens_->InitTraversal ();
00897 vtkRenderer* renderer = NULL;
00898 while ((renderer = rens_->GetNextItem ()) != NULL)
00899 {
00900 renderer->ResetCamera ();
00901 }
00902 }
00903
00905 bool
00906 pcl_visualization::PCLVisualizer::getCameraParameters (int argc, char **argv)
00907 {
00908 for (int i = 1; i < argc; i++)
00909 {
00910 if ((strcmp (argv[i], "-cam") == 0) && (++i < argc))
00911 {
00912 std::ifstream fs;
00913 std::string camfile = std::string (argv[i]);
00914 std::string line;
00915
00916 std::vector<std::string> camera;
00917 if (camfile.find (".cam") == std::string::npos)
00918 {
00919
00920 boost::split (camera, argv[i], boost::is_any_of ("/"), boost::token_compress_on);
00921 }
00922 else
00923 {
00924
00925 fs.open (camfile.c_str ());
00926 while (!fs.eof ())
00927 {
00928 getline (fs, line);
00929 if (line == "")
00930 continue;
00931
00932 boost::split (camera, line, boost::is_any_of ("/"), boost::token_compress_on);
00933 break;
00934 }
00935 fs.close ();
00936 }
00937
00938
00939 if (camera.size () != 6)
00940 {
00941 terminal_tools::print_error ("[PCLVisualizer::getCameraParameters] Camera parameters given, but with an invalid number of options (%zu vs 6)!\n", camera.size ());
00942 return (false);
00943 }
00944
00945 std::string clip_str = camera.at (0);
00946 std::string focal_str = camera.at (1);
00947 std::string pos_str = camera.at (2);
00948 std::string view_str = camera.at (3);
00949 std::string win_size_str = camera.at (4);
00950 std::string win_pos_str = camera.at (5);
00951
00952
00953 std::vector<std::string> clip_st;
00954 boost::split (clip_st, clip_str, boost::is_any_of (","), boost::token_compress_on);
00955 if (clip_st.size () != 2)
00956 {
00957 terminal_tools::print_error ("[PCLVisualizer::getCameraParameters] Invalid parameters given for camera clipping angle!\n");
00958 return (false);
00959 }
00960 camera_.clip[0] = atof (clip_st.at (0).c_str ());
00961 camera_.clip[1] = atof (clip_st.at (1).c_str ());
00962
00963 std::vector<std::string> focal_st;
00964 boost::split (focal_st, focal_str, boost::is_any_of (","), boost::token_compress_on);
00965 if (focal_st.size () != 3)
00966 {
00967 terminal_tools::print_error ("[PCLVisualizer::getCameraParameters] Invalid parameters given for camera focal point!\n");
00968 return (false);
00969 }
00970 camera_.focal[0] = atof (focal_st.at (0).c_str ());
00971 camera_.focal[1] = atof (focal_st.at (1).c_str ());
00972 camera_.focal[2] = atof (focal_st.at (2).c_str ());
00973
00974 std::vector<std::string> pos_st;
00975 boost::split (pos_st, pos_str, boost::is_any_of (","), boost::token_compress_on);
00976 if (pos_st.size () != 3)
00977 {
00978 terminal_tools::print_error ("[PCLVisualizer::getCameraParameters] Invalid parameters given for camera position!\n");
00979 return (false);
00980 }
00981 camera_.pos[0] = atof (pos_st.at (0).c_str ());
00982 camera_.pos[1] = atof (pos_st.at (1).c_str ());
00983 camera_.pos[2] = atof (pos_st.at (2).c_str ());
00984
00985 std::vector<std::string> view_st;
00986 boost::split (view_st, view_str, boost::is_any_of (","), boost::token_compress_on);
00987 if (view_st.size () != 3)
00988 {
00989 terminal_tools::print_error ("[PCLVisualizer::getCameraParameters] Invalid parameters given for camera viewup!\n");
00990 return (false);
00991 }
00992 camera_.view[0] = atof (view_st.at (0).c_str ());
00993 camera_.view[1] = atof (view_st.at (1).c_str ());
00994 camera_.view[2] = atof (view_st.at (2).c_str ());
00995
00996 std::vector<std::string> win_size_st;
00997 boost::split (win_size_st, win_size_str, boost::is_any_of (","), boost::token_compress_on);
00998 if (win_size_st.size () != 2)
00999 {
01000 terminal_tools::print_error ("[PCLVisualizer::getCameraParameters] Invalid parameters given for window size!\n");
01001 return (false);
01002 }
01003 camera_.window_size[0] = atof (win_size_st.at (0).c_str ());
01004 camera_.window_size[1] = atof (win_size_st.at (1).c_str ());
01005
01006 std::vector<std::string> win_pos_st;
01007 boost::split (win_pos_st, win_pos_str, boost::is_any_of (","), boost::token_compress_on);
01008 if (win_pos_st.size () != 2)
01009 {
01010 terminal_tools::print_error ("[PCLVisualizer::getCameraParameters] Invalid parameters given for window position!\n");
01011 return (false);
01012 }
01013 camera_.window_pos[0] = atof (win_pos_st.at (0).c_str ());
01014 camera_.window_pos[1] = atof (win_pos_st.at (1).c_str ());
01015
01016 return (true);
01017 }
01018 }
01019 return (false);
01020 }
01021
01023 bool
01024 pcl_visualization::PCLVisualizer::addCylinder (const pcl::ModelCoefficients &coefficients, const std::string &id, int viewport)
01025 {
01026
01027 ShapeActorMap::iterator am_it = shape_actor_map_.find (id);
01028 if (am_it != shape_actor_map_.end ())
01029 {
01030 terminal_tools::print_warn ("[addCylinder] A shape with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ());
01031 return (false);
01032 }
01033
01034 vtkSmartPointer<vtkDataSet> data = createCylinder (coefficients);
01035
01036
01037 vtkSmartPointer<vtkLODActor> actor;
01038 createActorFromVTKDataSet (data, actor);
01039 actor->GetProperty ()->SetRepresentationToWireframe ();
01040 addActorToRenderer (actor, viewport);
01041
01042
01043 shape_actor_map_[id] = actor;
01044 return (true);
01045 }
01046
01048 bool
01049 pcl_visualization::PCLVisualizer::addSphere (const pcl::ModelCoefficients &coefficients, const std::string &id, int viewport)
01050 {
01051
01052 ShapeActorMap::iterator am_it = shape_actor_map_.find (id);
01053 if (am_it != shape_actor_map_.end ())
01054 {
01055 terminal_tools::print_warn ("[addSphere] A shape with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ());
01056 return (false);
01057 }
01058
01059 vtkSmartPointer<vtkDataSet> data = createSphere (coefficients);
01060
01061
01062 vtkSmartPointer<vtkLODActor> actor;
01063 createActorFromVTKDataSet (data, actor);
01064 actor->GetProperty ()->SetRepresentationToWireframe ();
01065 addActorToRenderer (actor, viewport);
01066
01067
01068 shape_actor_map_[id] = actor;
01069 return (true);
01070 }
01071
01073 bool
01074 pcl_visualization::PCLVisualizer::addModelFromPLYFile (const std::string &filename, const std::string &id, int viewport)
01075 {
01076 ShapeActorMap::iterator am_it = shape_actor_map_.find (id);
01077 if (am_it != shape_actor_map_.end ())
01078 {
01079 terminal_tools::print_warn (
01080 "[addModelFromPLYFile] A shape with id <%s> already exists! Please choose a different id and retry.\n",
01081 id.c_str ());
01082 return (false);
01083 }
01084
01085 vtkSmartPointer < vtkPLYReader > reader = vtkSmartPointer<vtkPLYReader>::New ();
01086 reader->SetFileName (filename.c_str ());
01087
01088
01089 vtkSmartPointer < vtkLODActor > actor;
01090 createActorFromVTKDataSet (reader->GetOutput (), actor);
01091 actor->GetProperty ()->SetRepresentationToWireframe ();
01092 addActorToRenderer (actor, viewport);
01093
01094
01095 shape_actor_map_[id] = actor;
01096 return (true);
01097 }
01098
01100 bool
01101 pcl_visualization::PCLVisualizer::addModelFromPLYFile (const std::string &filename,
01102 vtkSmartPointer<vtkTransform> transform, const std::string &id,
01103 int viewport)
01104 {
01105 ShapeActorMap::iterator am_it = shape_actor_map_.find (id);
01106 if (am_it != shape_actor_map_.end ())
01107 {
01108 terminal_tools::print_warn (
01109 "[addModelFromPLYFile] A shape with id <%s> already exists! Please choose a different id and retry.\n",
01110 id.c_str ());
01111 return (false);
01112 }
01113
01114 vtkSmartPointer < vtkPLYReader > reader = vtkSmartPointer<vtkPLYReader>::New ();
01115 reader->SetFileName (filename.c_str ());
01116
01117
01118 vtkSmartPointer < vtkTransformFilter > trans_filter = vtkSmartPointer<vtkTransformFilter>::New ();
01119 trans_filter->SetTransform (transform);
01120 trans_filter->SetInputConnection (reader->GetOutputPort ());
01121
01122
01123 vtkSmartPointer < vtkLODActor > actor;
01124 createActorFromVTKDataSet (trans_filter->GetOutput (), actor);
01125 actor->GetProperty ()->SetRepresentationToWireframe ();
01126 addActorToRenderer (actor, viewport);
01127
01128
01129 shape_actor_map_[id] = actor;
01130 return (true);
01131 }
01132
01134 bool
01135 pcl_visualization::PCLVisualizer::addLine (const pcl::ModelCoefficients &coefficients, const std::string &id, int viewport)
01136 {
01137
01138 ShapeActorMap::iterator am_it = shape_actor_map_.find (id);
01139 if (am_it != shape_actor_map_.end ())
01140 {
01141 terminal_tools::print_warn ("[addLine] A shape with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ());
01142 return (false);
01143 }
01144
01145 vtkSmartPointer<vtkDataSet> data = createLine (coefficients);
01146
01147
01148 vtkSmartPointer<vtkLODActor> actor;
01149 createActorFromVTKDataSet (data, actor);
01150 actor->GetProperty ()->SetRepresentationToWireframe ();
01151 addActorToRenderer (actor, viewport);
01152
01153
01154 shape_actor_map_[id] = actor;
01155 return (true);
01156 }
01157
01159
01164 bool
01165 pcl_visualization::PCLVisualizer::addPlane (const pcl::ModelCoefficients &coefficients, const std::string &id, int viewport)
01166 {
01167
01168 ShapeActorMap::iterator am_it = shape_actor_map_.find (id);
01169 if (am_it != shape_actor_map_.end ())
01170 {
01171 terminal_tools::print_warn ("[addPlane] A shape with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ());
01172 return (false);
01173 }
01174
01175 vtkSmartPointer<vtkDataSet> data = createPlane (coefficients);
01176
01177
01178 vtkSmartPointer<vtkLODActor> actor;
01179 createActorFromVTKDataSet (data, actor);
01180 actor->GetProperty ()->SetRepresentationToWireframe ();
01181 addActorToRenderer (actor, viewport);
01182
01183
01184 shape_actor_map_[id] = actor;
01185 return (true);
01186 }
01187
01189 bool
01190 pcl_visualization::PCLVisualizer::addCircle (const pcl::ModelCoefficients &coefficients, const std::string &id, int viewport)
01191 {
01192
01193 ShapeActorMap::iterator am_it = shape_actor_map_.find (id);
01194 if (am_it != shape_actor_map_.end ())
01195 {
01196 terminal_tools::print_warn ("[addCircle] A shape with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ());
01197 return (false);
01198 }
01199
01200 vtkSmartPointer<vtkDataSet> data = create2DCircle (coefficients);
01201
01202
01203 vtkSmartPointer<vtkLODActor> actor;
01204 createActorFromVTKDataSet (data, actor);
01205 actor->GetProperty ()->SetRepresentationToWireframe ();
01206 addActorToRenderer (actor, viewport);
01207
01208
01209 shape_actor_map_[id] = actor;
01210 return (true);
01211 }
01212
01214 bool
01215 pcl_visualization::PCLVisualizer::addCone (const pcl::ModelCoefficients &coefficients, const std::string &id, int viewport)
01216 {
01217
01218 ShapeActorMap::iterator am_it = shape_actor_map_.find (id);
01219 if (am_it != shape_actor_map_.end ())
01220 {
01221 terminal_tools::print_warn ("[addCone] A shape with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ());
01222 return (false);
01223 }
01224
01225 vtkSmartPointer<vtkDataSet> data = createCone (coefficients);
01226
01227
01228 vtkSmartPointer<vtkLODActor> actor;
01229 createActorFromVTKDataSet (data, actor);
01230 actor->GetProperty ()->SetRepresentationToWireframe ();
01231 addActorToRenderer (actor, viewport);
01232
01233
01234 shape_actor_map_[id] = actor;
01235 return (true);
01236 }
01237
01239 void
01240 pcl_visualization::PCLVisualizer::createViewPort (double xmin, double ymin, double xmax, double ymax, int &viewport)
01241 {
01242
01243 vtkSmartPointer<vtkRenderer> ren = vtkSmartPointer<vtkRenderer>::New ();
01244 ren->SetViewport (xmin, ymin, xmax, ymax);
01245
01246 if (rens_->GetNumberOfItems () > 0)
01247 ren->SetActiveCamera (rens_->GetFirstRenderer ()->GetActiveCamera ());
01248 ren->ResetCamera ();
01249
01250
01251 rens_->AddItem (ren);
01252
01253 if (rens_->GetNumberOfItems () <= 1)
01254 viewport = 0;
01255 else
01256 viewport = rens_->GetNumberOfItems ();
01257
01258 win_->AddRenderer (ren);
01259 win_->Modified ();
01260 }
01261
01263 bool
01264 pcl_visualization::PCLVisualizer::addText (const std::string &text, int xpos, int ypos, const std::string &id, int viewport)
01265 {
01266 std::string tid;
01267 if (id.empty ())
01268 tid = text;
01269 else
01270 tid = id;
01271
01272
01273 ShapeActorMap::iterator am_it = shape_actor_map_.find (tid);
01274 if (am_it != shape_actor_map_.end ())
01275 {
01276 terminal_tools::print_warn ("[addText] A text with id <%s> already exists! Please choose a different id and retry.\n", tid.c_str ());
01277 return (false);
01278 }
01279
01280
01281 vtkSmartPointer<vtkTextActor> actor = vtkSmartPointer<vtkTextActor>::New ();
01282 actor->SetPosition (xpos, ypos);
01283 actor->SetInput (text.c_str ());
01284
01285 vtkSmartPointer<vtkTextProperty> tprop = actor->GetTextProperty ();
01286 tprop->SetFontSize (10);
01287 tprop->SetFontFamilyToArial ();
01288 tprop->SetJustificationToLeft ();
01289 tprop->BoldOn ();
01290 tprop->SetColor (1, 1, 1);
01291 addActorToRenderer (actor, viewport);
01292
01293
01294 shape_actor_map_[tid] = actor;
01295 return (true);
01296 }
01297
01299 bool
01300 pcl_visualization::PCLVisualizer::addText (const std::string &text, int xpos, int ypos, int r, int g, int b, const std::string &id, int viewport)
01301 {
01302 std::string tid;
01303 if (id.empty ())
01304 tid = text;
01305 else
01306 tid = id;
01307
01308
01309 ShapeActorMap::iterator am_it = shape_actor_map_.find (tid);
01310 if (am_it != shape_actor_map_.end ())
01311 {
01312 terminal_tools::print_warn ("[addText] A text with id <%s> already exists! Please choose a different id and retry.\n", tid.c_str ());
01313 return (false);
01314 }
01315
01316
01317 vtkSmartPointer<vtkTextActor> actor = vtkSmartPointer<vtkTextActor>::New ();
01318 actor->SetPosition (xpos, ypos);
01319 actor->SetInput (text.c_str ());
01320
01321 vtkSmartPointer<vtkTextProperty> tprop = actor->GetTextProperty ();
01322 tprop->SetFontSize (10);
01323 tprop->SetFontFamilyToArial ();
01324 tprop->SetJustificationToLeft ();
01325 tprop->BoldOn ();
01326 tprop->SetColor (r, g, b);
01327 addActorToRenderer (actor, viewport);
01328
01329
01330 shape_actor_map_[tid] = actor;
01331 return (true);
01332 }
01333
01335 bool
01336 pcl_visualization::PCLVisualizer::updateColorHandlerIndex (const std::string &id, int index)
01337 {
01338 CloudActorMap::iterator am_it = cloud_actor_map_.find (id);
01339 if (am_it == cloud_actor_map_.end ())
01340 {
01341 terminal_tools::print_warn ("[updateColorHandlerIndex] PointCloud with id <%s> doesn't exist!\n", id.c_str ());
01342 return (false);
01343 }
01344
01345 if (index >= (int)am_it->second.color_handlers.size ())
01346 {
01347 terminal_tools::print_warn ("[updateColorHandlerIndex] Invalid index <%d> given! Maximum range is: 0-%zu.\n", index, am_it->second.color_handlers.size ());
01348 return (false);
01349 }
01350
01351 PointCloudColorHandler<sensor_msgs::PointCloud2>::ConstPtr color_handler = am_it->second.color_handlers[index];
01352
01353 vtkSmartPointer<vtkDataArray> scalars;
01354 color_handler->getColor (scalars);
01355 double minmax[2];
01356 scalars->GetRange (minmax);
01357
01358 vtkPolyData *data = static_cast<vtkPolyData*>(am_it->second.actor->GetMapper ()->GetInput ());
01359 data->GetPointData ()->SetScalars (scalars);
01360 data->Update ();
01361
01362 vtkPolyDataMapper* mapper = static_cast<vtkPolyDataMapper*>(am_it->second.actor->GetMapper ());
01363 mapper->SetScalarRange (minmax);
01364 mapper->SetScalarModeToUsePointData ();
01365 mapper->SetInput (data);
01366
01367 am_it->second.actor->SetMapper (mapper);
01368 am_it->second.actor->Modified ();
01369 am_it->second.color_handler_index_ = index;
01370
01371 style_->setCloudActorMap (boost::make_shared<CloudActorMap> (cloud_actor_map_));
01372
01373 return (true);
01374 }
01375
01379 void
01380 pcl_visualization::FPSCallback::Execute (vtkObject *caller, unsigned long, void*)
01381 {
01382 vtkRenderer *ren = reinterpret_cast<vtkRenderer *> (caller);
01383 float fps = 1.0 / ren->GetLastRenderTimeInSeconds ();
01384 char buf[128];
01385 snprintf (buf, 127, "%.1f FPS", fps);
01386 actor_->SetInput (buf);
01387 }
01388