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
00039 #include <vtkImageViewer.h>
00040 #include <vtkCallbackCommand.h>
00041 #include <vtkRenderer.h>
00042 #include <vtkCamera.h>
00043
00044 #include <pcl/visualization/image_viewer.h>
00045 #include <pcl/visualization/common/float_image_utils.h>
00046 #include <pcl/visualization/keyboard_event.h>
00047 #include <pcl/visualization/mouse_event.h>
00048 #include <pcl/common/time.h>
00049 #include <pcl/visualization/vtk/vtkRenderWindowInteractorFix.h>
00050
00052 pcl::visualization::ImageViewer::ImageViewer (const std::string& window_title)
00053 : interactor_ ()
00054 , mouse_command_ (vtkSmartPointer<vtkCallbackCommand>::New ())
00055 , keyboard_command_ (vtkSmartPointer<vtkCallbackCommand>::New ())
00056 , exit_main_loop_timer_callback_ ()
00057 , exit_callback_ ()
00058 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 10))
00059 , image_viewer_ (vtkSmartPointer<vtkImageViewer>::New ())
00060 #else
00061 , win_ (vtkSmartPointer<vtkRenderWindow>::New ())
00062 , ren_ (vtkSmartPointer<vtkRenderer>::New ())
00063 , slice_ (vtkSmartPointer<vtkImageSlice>::New ())
00064 #endif
00065 , interactor_style_ (vtkSmartPointer<ImageViewerInteractorStyle>::New ())
00066 , data_ ()
00067 , data_size_ (0)
00068 , stopped_ ()
00069 , timer_id_ ()
00070 , layer_map_ ()
00071 , algo_ (vtkSmartPointer<vtkImageFlip>::New ())
00072 , image_data_ ()
00073 {
00074 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00075 interactor_ = vtkSmartPointer<PCLVisualizerInteractor>::New ();
00076 #else
00077 interactor_ = vtkSmartPointer <vtkRenderWindowInteractor>::Take (vtkRenderWindowInteractorFixNew ());
00078 #endif
00079
00080
00081 algo_->SetInterpolationModeToCubic ();
00082 algo_->PreserveImageExtentOn ();
00083 algo_->FlipAboutOriginOn ();
00084 algo_->SetFilteredAxis (1);
00085
00086
00087
00088 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 10))
00089 image_viewer_->SetColorLevel (127.5);
00090 image_viewer_->SetColorWindow (255);
00091 #endif
00092
00093
00094 mouse_command_->SetClientData (this);
00095 mouse_command_->SetCallback (ImageViewer::MouseCallback);
00096
00097 keyboard_command_->SetClientData (this);
00098 keyboard_command_->SetCallback (ImageViewer::KeyboardCallback);
00099
00100
00101 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 10))
00102 image_viewer_->SetupInteractor (interactor_);
00103 image_viewer_->GetRenderWindow ()->SetWindowName (window_title.c_str ());
00104 image_viewer_->GetRenderWindow ()->DoubleBufferOn ();
00105 image_viewer_->GetRenderWindow ()->EraseOff ();
00106 image_viewer_->GetRenderWindow ()->SetSize (640, 480);
00107 ren_ = image_viewer_->GetRenderer ();
00108 win_ = image_viewer_->GetRenderWindow ();
00109 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION >= 5))
00110 interactor_ = win_->GetInteractor ();
00111 #endif
00112 #else
00113 win_->SetSize (640, 480);
00114 win_->AddRenderer (ren_);
00115 win_->SetWindowName (window_title.c_str ());
00116 interactor_->SetRenderWindow (win_);
00117
00118 vtkSmartPointer<vtkImageData> empty_image = vtkSmartPointer<vtkImageData>::New ();
00119 vtkSmartPointer<vtkImageSliceMapper> map = vtkSmartPointer<vtkImageSliceMapper>::New ();
00120 map->SetInput (empty_image);
00121 slice_->SetMapper (map);
00122 ren_->AddViewProp (slice_);
00123 interactor_->SetInteractorStyle (interactor_style_);
00124 #endif
00125
00126
00127 interactor_->Initialize ();
00128 timer_id_ = interactor_->CreateRepeatingTimer (0);
00129
00130
00131 exit_main_loop_timer_callback_ = vtkSmartPointer<ExitMainLoopTimerCallback>::New ();
00132 exit_main_loop_timer_callback_->window = this;
00133 exit_main_loop_timer_callback_->right_timer_id = -1;
00134 interactor_->AddObserver (vtkCommand::TimerEvent, exit_main_loop_timer_callback_);
00135
00136 exit_callback_ = vtkSmartPointer<ExitCallback>::New ();
00137 exit_callback_->window = this;
00138 interactor_->AddObserver (vtkCommand::ExitEvent, exit_callback_);
00139
00140
00141 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION > 10))
00142
00143 vtkSmartPointer<vtkTransform> transform = vtkSmartPointer<vtkTransform>::New ();
00144 transform->Scale (1.0, -1.0, 1.0);
00145 ren_->GetActiveCamera ()->SetUserTransform (transform);
00146 ren_->GetActiveCamera ()->ParallelProjectionOn ();
00147 ren_->ResetCamera ();
00148 ren_->ResetCameraClippingRange ();
00149 #endif
00150 resetStoppedFlag ();
00151
00152 PCL_DEBUG ("[pcl::visualization::ImageViewer] VTK version found: %d.%d\n", VTK_MAJOR_VERSION, VTK_MINOR_VERSION);
00153 }
00154
00156 pcl::visualization::ImageViewer::~ImageViewer ()
00157 {
00158 interactor_->DestroyTimer (timer_id_);
00159 }
00160
00162 void
00163 pcl::visualization::ImageViewer::addRGBImage (
00164 const unsigned char* rgb_data, unsigned width, unsigned height,
00165 const std::string &layer_id, double opacity)
00166 {
00167 if (unsigned (getSize ()[0]) != width ||
00168 unsigned (getSize ()[1]) != height)
00169 setSize (width, height);
00170
00171
00172 LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00173 if (am_it == layer_map_.end ())
00174 {
00175 PCL_DEBUG ("[pcl::visualization::ImageViewer::addRGBImage] No layer with ID='%s' found. Creating new one...\n", layer_id.c_str ());
00176 am_it = createLayer (layer_id, width, height, opacity, false);
00177 }
00178
00179 void* data = const_cast<void*> (reinterpret_cast<const void*> (rgb_data));
00180
00181 vtkSmartPointer<vtkImageData> image = vtkSmartPointer<vtkImageData>::New ();
00182 image->SetExtent (0, width - 1, 0, height - 1, 0, 0);
00183 image->SetScalarTypeToUnsignedChar ();
00184 image->SetNumberOfScalarComponents (3);
00185 image->AllocateScalars ();
00186 image->GetPointData ()->GetScalars ()->SetVoidArray (data, 3 * width * height, 1);
00187 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 10))
00188
00189 algo_->SetInput (image);
00190 algo_->Update ();
00191 # if (VTK_MINOR_VERSION <= 6)
00192 image_viewer_->SetInput (algo_->GetOutput ());
00193 # else
00194 image_viewer_->SetInputConnection (algo_->GetOutputPort ());
00195 # endif
00196 #else
00197 image_viewer_->SetInputData (image);
00198 interactor_style_->adjustCamera (image, ren_);
00199 #endif
00200 }
00201
00203 void
00204 pcl::visualization::ImageViewer::showRGBImage (
00205 const unsigned char* rgb_data, unsigned width, unsigned height,
00206 const std::string &layer_id, double opacity)
00207 {
00208 addRGBImage (rgb_data, width, height, layer_id, opacity);
00209 render ();
00210 }
00211
00213 void
00214 pcl::visualization::ImageViewer::addMonoImage (
00215 const unsigned char* rgb_data, unsigned width, unsigned height,
00216 const std::string &layer_id, double opacity)
00217 {
00218 if (unsigned (getSize ()[0]) != width ||
00219 unsigned (getSize ()[1]) != height)
00220 setSize (width, height);
00221
00222
00223 LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00224 if (am_it == layer_map_.end ())
00225 {
00226 PCL_DEBUG ("[pcl::visualization::ImageViewer::showMonoImage] No layer with ID='%s' found. Creating new one...\n", layer_id.c_str ());
00227 am_it = createLayer (layer_id, width, height, opacity, false);
00228 }
00229
00230 void* data = const_cast<void*> (reinterpret_cast<const void*> (rgb_data));
00231
00232 vtkSmartPointer<vtkImageData> image = vtkSmartPointer<vtkImageData>::New ();
00233 image->SetExtent (0, width - 1, 0, height - 1, 0, 0);
00234 image->SetScalarTypeToUnsignedChar ();
00235 image->SetNumberOfScalarComponents (1);
00236 image->AllocateScalars ();
00237 image->GetPointData ()->GetScalars ()->SetVoidArray (data, width * height, 1);
00238
00239 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 10))
00240
00241 algo_->SetInput (image);
00242 algo_->Update ();
00243 # if (VTK_MINOR_VERSION <= 6)
00244 image_viewer_->SetInput (algo_->GetOutput ());
00245 # else
00246 image_viewer_->SetInputConnection (algo_->GetOutputPort ());
00247 # endif
00248 #else
00249 image_viewer_->SetInputData (image);
00250 interactor_style_->adjustCamera (image, ren_);
00251 #endif
00252 }
00253
00254
00256 void
00257 pcl::visualization::ImageViewer::showMonoImage (
00258 const unsigned char* rgb_data, unsigned width, unsigned height,
00259 const std::string &layer_id, double opacity)
00260 {
00261 addMonoImage (rgb_data, width, height, layer_id, opacity);
00262 render ();
00263 }
00264
00266 void
00267 pcl::visualization::ImageViewer::addMonoImage (
00268 const pcl::PointCloud<pcl::Intensity> &cloud,
00269 const std::string &layer_id, double opacity)
00270 {
00271 if (data_size_ < cloud.width * cloud.height)
00272 {
00273 data_size_ = cloud.width * cloud.height * 3;
00274 data_.reset (new unsigned char[data_size_]);
00275 }
00276
00277 convertIntensityCloudToUChar (cloud, data_);
00278
00279 return (addMonoImage (data_.get (), cloud.width, cloud.height, layer_id, opacity));
00280 }
00281
00283 void
00284 pcl::visualization::ImageViewer::showMonoImage (
00285 const pcl::PointCloud<pcl::Intensity> &cloud,
00286 const std::string &layer_id, double opacity)
00287 {
00288 addMonoImage (cloud, layer_id, opacity);
00289 render ();
00290 }
00291
00293 void
00294 pcl::visualization::ImageViewer::addMonoImage (
00295 const pcl::PointCloud<pcl::Intensity8u> &cloud,
00296 const std::string &layer_id, double opacity)
00297 {
00298 if (data_size_ < cloud.width * cloud.height)
00299 {
00300 data_size_ = cloud.width * cloud.height * 3;
00301 data_.reset (new unsigned char[data_size_]);
00302 }
00303
00304 convertIntensityCloud8uToUChar (cloud, data_);
00305
00306 return (addMonoImage (data_.get (), cloud.width, cloud.height, layer_id, opacity));
00307 }
00308
00310 void
00311 pcl::visualization::ImageViewer::showMonoImage (
00312 const pcl::PointCloud<pcl::Intensity8u> &cloud,
00313 const std::string &layer_id, double opacity)
00314 {
00315 addMonoImage (cloud, layer_id, opacity);
00316 render ();
00317 }
00318
00320 void
00321 pcl::visualization::ImageViewer::addFloatImage (
00322 const float* float_image, unsigned int width, unsigned int height,
00323 float min_value, float max_value, bool grayscale,
00324 const std::string &layer_id, double opacity)
00325 {
00326 unsigned char* rgb_image = FloatImageUtils::getVisualImage (float_image, width, height,
00327 min_value, max_value, grayscale);
00328 addRGBImage (rgb_image, width, height, layer_id, opacity);
00329 image_data_.push_back (rgb_image);
00330 }
00331
00333 void
00334 pcl::visualization::ImageViewer::showFloatImage (
00335 const float* float_image, unsigned int width, unsigned int height,
00336 float min_value, float max_value, bool grayscale,
00337 const std::string &layer_id, double opacity)
00338 {
00339 addFloatImage (float_image, width, height, min_value, max_value, grayscale, layer_id, opacity);
00340 render ();
00341 }
00342
00344 void
00345 pcl::visualization::ImageViewer::addAngleImage (
00346 const float* angle_image, unsigned int width, unsigned int height,
00347 const std::string &layer_id, double opacity)
00348 {
00349 unsigned char* rgb_image = FloatImageUtils::getVisualAngleImage (angle_image, width, height);
00350 addRGBImage (rgb_image, width, height, layer_id, opacity);
00351 image_data_.push_back (rgb_image);
00352 }
00353
00355 void
00356 pcl::visualization::ImageViewer::showAngleImage (
00357 const float* angle_image, unsigned int width, unsigned int height,
00358 const std::string &layer_id, double opacity)
00359 {
00360 addAngleImage (angle_image, width, height, layer_id, opacity);
00361 render ();
00362 }
00363
00365 void
00366 pcl::visualization::ImageViewer::addHalfAngleImage (
00367 const float* angle_image, unsigned int width, unsigned int height,
00368 const std::string &layer_id, double opacity)
00369 {
00370 unsigned char* rgb_image = FloatImageUtils::getVisualHalfAngleImage (angle_image, width, height);
00371 addRGBImage (rgb_image, width, height, layer_id, opacity);
00372 image_data_.push_back (rgb_image);
00373 }
00374
00376 void
00377 pcl::visualization::ImageViewer::showHalfAngleImage (
00378 const float* angle_image, unsigned int width, unsigned int height,
00379 const std::string &layer_id, double opacity)
00380 {
00381 addHalfAngleImage (angle_image, width, height, layer_id, opacity);
00382 render ();
00383 }
00384
00386 void
00387 pcl::visualization::ImageViewer::addShortImage (
00388 const unsigned short* short_image, unsigned int width, unsigned int height,
00389 unsigned short min_value, unsigned short max_value, bool grayscale,
00390 const std::string &layer_id, double opacity)
00391 {
00392 unsigned char* rgb_image = FloatImageUtils::getVisualImage (short_image, width, height,
00393 min_value, max_value, grayscale);
00394 addRGBImage (rgb_image, width, height, layer_id, opacity);
00395 image_data_.push_back (rgb_image);
00396 }
00397
00399 void
00400 pcl::visualization::ImageViewer::showShortImage (
00401 const unsigned short* short_image, unsigned int width, unsigned int height,
00402 unsigned short min_value, unsigned short max_value, bool grayscale,
00403 const std::string &layer_id, double opacity)
00404 {
00405 addShortImage (short_image, width, height, min_value, max_value, grayscale, layer_id, opacity);
00406 render ();
00407 }
00408
00410 void
00411 pcl::visualization::ImageViewer::spin ()
00412 {
00413 render ();
00414 resetStoppedFlag ();
00415
00416
00417 interactor_->Start ();
00418 }
00419
00421 void
00422 pcl::visualization::ImageViewer::spinOnce (int time, bool force_redraw)
00423 {
00424 if (force_redraw)
00425 {
00426 render ();
00427
00428 }
00429
00430 if (time <= 0)
00431 time = 1;
00432
00433 DO_EVERY (1.0 / interactor_->GetDesiredUpdateRate (),
00434 exit_main_loop_timer_callback_->right_timer_id = interactor_->CreateRepeatingTimer (time);
00435 interactor_->Start ();
00436 interactor_->DestroyTimer (exit_main_loop_timer_callback_->right_timer_id);
00437 );
00438 for(unsigned int i = 0; i < image_data_.size(); i++)
00439 delete [] image_data_[i];
00440 image_data_.clear ();
00441 }
00442
00444 boost::signals2::connection
00445 pcl::visualization::ImageViewer::registerMouseCallback (
00446 boost::function<void (const pcl::visualization::MouseEvent&)> callback)
00447 {
00448
00449 if (mouse_signal_.empty ())
00450 {
00451 interactor_->AddObserver (vtkCommand::MouseMoveEvent, mouse_command_);
00452 interactor_->AddObserver (vtkCommand::MiddleButtonPressEvent, mouse_command_);
00453 interactor_->AddObserver (vtkCommand::MiddleButtonReleaseEvent, mouse_command_);
00454 interactor_->AddObserver (vtkCommand::MouseWheelBackwardEvent, mouse_command_);
00455 interactor_->AddObserver (vtkCommand::MouseWheelForwardEvent, mouse_command_);
00456 interactor_->AddObserver (vtkCommand::LeftButtonPressEvent, mouse_command_);
00457 interactor_->AddObserver (vtkCommand::LeftButtonReleaseEvent, mouse_command_);
00458 interactor_->AddObserver (vtkCommand::RightButtonPressEvent, mouse_command_);
00459 interactor_->AddObserver (vtkCommand::RightButtonReleaseEvent, mouse_command_);
00460 }
00461 return (mouse_signal_.connect (callback));
00462 }
00463
00465 boost::signals2::connection
00466 pcl::visualization::ImageViewer::registerKeyboardCallback (
00467 boost::function<void (const pcl::visualization::KeyboardEvent&)> callback)
00468 {
00469
00470 if (keyboard_signal_.empty ())
00471 {
00472 interactor_->AddObserver (vtkCommand::KeyPressEvent, keyboard_command_);
00473 interactor_->AddObserver (vtkCommand::KeyReleaseEvent, keyboard_command_);
00474 }
00475
00476 return (keyboard_signal_.connect (callback));
00477 }
00478
00480 void
00481 pcl::visualization::ImageViewer::emitMouseEvent (unsigned long event_id)
00482 {
00483
00484 int x = this->interactor_->GetEventPosition()[0];
00485 int y = this->interactor_->GetEventPosition()[1];
00486 MouseEvent event (MouseEvent::MouseMove, MouseEvent::NoButton, x, y,
00487 interactor_->GetAltKey (),
00488 interactor_->GetControlKey (),
00489 interactor_->GetShiftKey ());
00490 bool repeat = false;
00491 switch (event_id)
00492 {
00493 case vtkCommand::MouseMoveEvent :
00494 event.setType (MouseEvent::MouseMove);
00495 break;
00496
00497 case vtkCommand::LeftButtonPressEvent :
00498 event.setButton (MouseEvent::LeftButton);
00499 if (interactor_->GetRepeatCount () == 0)
00500 event.setType (MouseEvent::MouseButtonPress);
00501 else
00502 event.setType (MouseEvent::MouseDblClick);
00503 break;
00504
00505 case vtkCommand::LeftButtonReleaseEvent :
00506 event.setButton (MouseEvent::LeftButton);
00507 event.setType (MouseEvent::MouseButtonRelease);
00508 break;
00509
00510 case vtkCommand::RightButtonPressEvent :
00511 event.setButton (MouseEvent::RightButton);
00512 if (interactor_->GetRepeatCount () == 0)
00513 event.setType (MouseEvent::MouseButtonPress);
00514 else
00515 event.setType (MouseEvent::MouseDblClick);
00516 break;
00517
00518 case vtkCommand::RightButtonReleaseEvent :
00519 event.setButton (MouseEvent::RightButton);
00520 event.setType (MouseEvent::MouseButtonRelease);
00521 break;
00522
00523 case vtkCommand::MiddleButtonPressEvent :
00524 event.setButton (MouseEvent::MiddleButton);
00525 if (interactor_->GetRepeatCount () == 0)
00526 event.setType (MouseEvent::MouseButtonPress);
00527 else
00528 event.setType (MouseEvent::MouseDblClick);
00529 break;
00530
00531 case vtkCommand::MiddleButtonReleaseEvent :
00532 event.setButton (MouseEvent::MiddleButton);
00533 event.setType (MouseEvent::MouseButtonRelease);
00534 break;
00535
00536 case vtkCommand::MouseWheelBackwardEvent :
00537 event.setButton (MouseEvent::VScroll);
00538 event.setType (MouseEvent::MouseScrollDown);
00539 if (interactor_->GetRepeatCount () != 0)
00540 repeat = true;
00541 break;
00542
00543 case vtkCommand::MouseWheelForwardEvent :
00544 event.setButton (MouseEvent::VScroll);
00545 event.setType (MouseEvent::MouseScrollUp);
00546 if (interactor_->GetRepeatCount () != 0)
00547 repeat = true;
00548 break;
00549 default:
00550 return;
00551 }
00552
00553 mouse_signal_ (event);
00554 if (repeat)
00555 mouse_signal_ (event);
00556 }
00557
00559 void
00560 pcl::visualization::ImageViewer::emitKeyboardEvent (unsigned long event_id)
00561 {
00562 KeyboardEvent event (bool(event_id == vtkCommand::KeyPressEvent), interactor_->GetKeySym (), interactor_->GetKeyCode (), interactor_->GetAltKey (), interactor_->GetControlKey (), interactor_->GetShiftKey ());
00563 keyboard_signal_ (event);
00564 }
00565
00567 void
00568 pcl::visualization::ImageViewer::MouseCallback (vtkObject*, unsigned long eid, void* clientdata, void*)
00569 {
00570 ImageViewer* window = reinterpret_cast<ImageViewer*> (clientdata);
00571 window->emitMouseEvent (eid);
00572 }
00573
00575 void
00576 pcl::visualization::ImageViewer::KeyboardCallback (vtkObject*, unsigned long eid, void* clientdata, void*)
00577 {
00578 ImageViewer* window = reinterpret_cast<ImageViewer*> (clientdata);
00579 window->emitKeyboardEvent (eid);
00580 }
00581
00583 pcl::visualization::ImageViewer::LayerMap::iterator
00584 pcl::visualization::ImageViewer::createLayer (
00585 const std::string &layer_id, int width, int height, double opacity, bool fill_box)
00586 {
00587 Layer l;
00588 l.layer_name = layer_id;
00589
00590 l.actor = vtkSmartPointer<vtkContextActor>::New ();
00591 l.actor->PickableOff ();
00592 l.actor->DragableOff ();
00593 if (fill_box)
00594 {
00595 vtkSmartPointer<context_items::FilledRectangle> rect = vtkSmartPointer<context_items::FilledRectangle>::New ();
00596 rect->setColors (0,0,0);
00597 rect->setOpacity (opacity);
00598 rect->set (0, 0, static_cast<float> (width), static_cast<float> (height));
00599 l.actor->GetScene ()->AddItem (rect);
00600 }
00601 image_viewer_->GetRenderer ()->AddActor (l.actor);
00602
00603 layer_map_.push_back (l);
00604
00605 return (layer_map_.end () - 1);
00606 }
00607
00609 bool
00610 pcl::visualization::ImageViewer::addLayer (
00611 const std::string &layer_id, int width, int height, double opacity)
00612 {
00613
00614 LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00615 if (am_it != layer_map_.end ())
00616 {
00617 PCL_DEBUG ("[pcl::visualization::ImageViewer::addLayer] Layer with ID='%s' already exists!\n", layer_id.c_str ());
00618 return (false);
00619 }
00620
00621 createLayer (layer_id, width, height, opacity, false);
00622
00623 return (true);
00624 }
00625
00627 void
00628 pcl::visualization::ImageViewer::removeLayer (const std::string &layer_id)
00629 {
00630
00631 LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00632 if (am_it == layer_map_.end ())
00633 {
00634 PCL_DEBUG ("[pcl::visualization::ImageViewer::removeLayer] No layer with ID='%s' found.\n", layer_id.c_str ());
00635 return;
00636 }
00637 image_viewer_->GetRenderer ()->RemoveActor (am_it->actor);
00638 layer_map_.erase (am_it);
00639 }
00640
00642 bool
00643 pcl::visualization::ImageViewer::addCircle (
00644 unsigned int x, unsigned int y, double radius, double r, double g, double b,
00645 const std::string &layer_id, double opacity)
00646 {
00647
00648 LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00649 if (am_it == layer_map_.end ())
00650 {
00651 PCL_DEBUG ("[pcl::visualization::ImageViewer::addCircle] No layer with ID='%s' found. Creating new one...\n", layer_id.c_str ());
00652 am_it = createLayer (layer_id, getSize ()[0] - 1, getSize ()[1] - 1, opacity, false);
00653 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION > 10))
00654 interactor_style_->adjustCamera (ren_);
00655 #endif
00656 }
00657
00658 vtkSmartPointer<context_items::Circle> circle = vtkSmartPointer<context_items::Circle>::New ();
00659 circle->setColors (static_cast<unsigned char> (255.0 * r),
00660 static_cast<unsigned char> (255.0 * g),
00661 static_cast<unsigned char> (255.0 * b));
00662 circle->setOpacity (opacity);
00663 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION > 10))
00664 circle->set (static_cast<float> (x), static_cast<float> (y), static_cast<float> (radius));
00665 #else
00666 circle->set (static_cast<float> (x), static_cast<float> (getSize ()[1] - y), static_cast<float> (radius));
00667 #endif
00668 am_it->actor->GetScene ()->AddItem (circle);
00669
00670 return (true);
00671 }
00672
00674 bool
00675 pcl::visualization::ImageViewer::addCircle (unsigned int x, unsigned int y, double radius,
00676 const std::string &layer_id, double opacity)
00677 {
00678 return (addCircle (x, y, radius, layer_id, opacity));
00679 }
00680
00682 bool
00683 pcl::visualization::ImageViewer::addFilledRectangle (
00684 unsigned int x_min, unsigned int x_max, unsigned int y_min, unsigned int y_max,
00685 double r, double g, double b, const std::string &layer_id, double opacity)
00686 {
00687
00688 LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00689 if (am_it == layer_map_.end ())
00690 {
00691 PCL_DEBUG ("[pcl::visualization::ImageViewer::addFilledRectangle] No layer with ID='%s' found. Creating new one...\n", layer_id.c_str ());
00692 am_it = createLayer (layer_id, getSize ()[0] - 1, getSize ()[1] - 1, opacity, false);
00693 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION > 10))
00694 interactor_style_->adjustCamera (ren_);
00695 #endif
00696 }
00697
00698 vtkSmartPointer<context_items::FilledRectangle> rect = vtkSmartPointer<context_items::FilledRectangle>::New ();
00699 rect->setColors (static_cast<unsigned char> (255.0 * r),
00700 static_cast<unsigned char> (255.0 * g),
00701 static_cast<unsigned char> (255.0 * b));
00702 rect->setOpacity (opacity);
00703 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION > 10))
00704 rect->set (static_cast<float> (x_min), static_cast<float> (y_min),
00705 static_cast<float> (x_max - x_min), static_cast<float> (y_max - y_min));
00706 #else
00707 rect->set (static_cast<float> (x_min), static_cast<float> (getSize ()[1] - y_min),
00708 static_cast<float> (x_max - x_min), static_cast<float> (y_max - y_min));
00709 #endif
00710 am_it->actor->GetScene ()->AddItem (rect);
00711
00712 return (true);
00713 }
00714
00716 bool
00717 pcl::visualization::ImageViewer::addFilledRectangle (
00718 unsigned int x_min, unsigned int x_max, unsigned int y_min, unsigned int y_max,
00719 const std::string &layer_id, double opacity)
00720 {
00721 return (addFilledRectangle (x_min, x_max, y_min, y_max, 0.0, 1.0, 0.0, layer_id, opacity));
00722 }
00723
00725 bool
00726 pcl::visualization::ImageViewer::addRectangle (
00727 unsigned int x_min, unsigned int x_max, unsigned int y_min, unsigned int y_max,
00728 double r, double g, double b, const std::string &layer_id, double opacity)
00729 {
00730
00731 LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00732 if (am_it == layer_map_.end ())
00733 {
00734 PCL_DEBUG ("[pcl::visualization::ImageViewer::addRectangle] No layer with ID='%s' found. Creating new one...\n", layer_id.c_str ());
00735 am_it = createLayer (layer_id, getSize ()[0] - 1, getSize ()[1] - 1, opacity, false);
00736 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION > 10))
00737 interactor_style_->adjustCamera (ren_);
00738 #endif
00739 }
00740
00741 vtkSmartPointer<context_items::Rectangle> rect = vtkSmartPointer<context_items::Rectangle>::New ();
00742 rect->setColors (static_cast<unsigned char> (255.0 * r),
00743 static_cast<unsigned char> (255.0 * g),
00744 static_cast<unsigned char> (255.0 * b));
00745 rect->setOpacity (opacity);
00746 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION > 10))
00747 rect->set (static_cast<float> (x_min), static_cast<float> (y_min),
00748 static_cast<float> (x_max - x_min), static_cast<float> (y_max - y_min));
00749 #else
00750 rect->set (static_cast<float> (x_min), static_cast<float> (getSize ()[1] - y_min),
00751 static_cast<float> (x_max - x_min), static_cast<float> (y_max - y_min));
00752 #endif
00753 am_it->actor->GetScene ()->AddItem (rect);
00754
00755 return (true);
00756 }
00757
00759 bool
00760 pcl::visualization::ImageViewer::addRectangle (
00761 unsigned int x_min, unsigned int x_max, unsigned int y_min, unsigned int y_max,
00762 const std::string &layer_id, double opacity)
00763 {
00764 return (addRectangle (x_min, x_max, y_min, y_max, 0.0, 1.0, 0.0, layer_id, opacity));
00765 }
00766
00768 bool
00769 pcl::visualization::ImageViewer::addRectangle (
00770 const pcl::PointXY &min_pt, const pcl::PointXY &max_pt,
00771 double r, double g, double b, const std::string &layer_id, double opacity)
00772 {
00773
00774 LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00775 if (am_it == layer_map_.end ())
00776 {
00777 PCL_DEBUG ("[pcl::visualization::ImageViewer::addRectangle] No layer with ID='%s' found. Creating new one...\n", layer_id.c_str ());
00778 am_it = createLayer (layer_id, getSize ()[0] - 1, getSize ()[1] - 1, opacity, false);
00779 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION > 10))
00780 interactor_style_->adjustCamera (ren_);
00781 #endif
00782 }
00783
00784 vtkSmartPointer<context_items::Rectangle> rect = vtkSmartPointer<context_items::Rectangle>::New ();
00785 rect->setColors (static_cast<unsigned char> (255.0 * r),
00786 static_cast<unsigned char> (255.0 * g),
00787 static_cast<unsigned char> (255.0 * b));
00788 rect->setOpacity (opacity);
00789 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION > 10))
00790 rect->set (min_pt.x, min_pt.y, (max_pt.x - min_pt.x), (max_pt.y - min_pt.y));
00791 #else
00792 rect->set (min_pt.x, static_cast<float> (getSize ()[1]) - min_pt.y, (max_pt.x - min_pt.x), (max_pt.y - min_pt.y));
00793 #endif
00794 am_it->actor->GetScene ()->AddItem (rect);
00795
00796 return (true);
00797 }
00798
00800 bool
00801 pcl::visualization::ImageViewer::addRectangle (
00802 const pcl::PointXY &min_pt, const pcl::PointXY &max_pt,
00803 const std::string &layer_id, double opacity)
00804 {
00805 return (addRectangle (min_pt, max_pt, 0.0, 1.0, 0.0, layer_id, opacity));
00806 }
00807
00809 bool
00810 pcl::visualization::ImageViewer::addLine (unsigned int x_min, unsigned int y_min,
00811 unsigned int x_max, unsigned int y_max,
00812 double r, double g, double b,
00813 const std::string &layer_id, double opacity)
00814 {
00815
00816 LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00817 if (am_it == layer_map_.end ())
00818 {
00819 PCL_DEBUG ("[pcl::visualization::ImageViewer::addLine] No layer with ID='%s' found. Creating new one...\n", layer_id.c_str ());
00820 am_it = createLayer (layer_id, getSize ()[0] - 1, getSize ()[1] - 1, opacity, false);
00821 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION > 10))
00822 interactor_style_->adjustCamera (ren_);
00823 #endif
00824 }
00825
00826 vtkSmartPointer<context_items::Line> line = vtkSmartPointer<context_items::Line>::New ();
00827 line->setColors (static_cast<unsigned char> (255.0 * r),
00828 static_cast<unsigned char> (255.0 * g),
00829 static_cast<unsigned char> (255.0 * b));
00830 line->setOpacity (opacity);
00831 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION > 10))
00832 line->set (static_cast<float> (x_min), static_cast<float> (y_min),
00833 static_cast<float> (x_max), static_cast<float> (y_max));
00834 #else
00835 line->set (static_cast<float> (x_min), static_cast<float> (getSize ()[1] - y_min),
00836 static_cast<float> (x_max), static_cast<float> (getSize ()[1] - y_max));
00837 #endif
00838 am_it->actor->GetScene ()->AddItem (line);
00839
00840 return (true);
00841 }
00842
00844 bool
00845 pcl::visualization::ImageViewer::addLine (unsigned int x_min, unsigned int y_min,
00846 unsigned int x_max, unsigned int y_max,
00847 const std::string &layer_id, double opacity)
00848 {
00849 return (addLine (x_min, y_min, x_max, y_max, 0.0, 1.0, 0.0, layer_id, opacity));
00850 }
00851
00853 void
00854 pcl::visualization::ImageViewer::markPoint (
00855 size_t u, size_t v, Vector3ub fg_color, Vector3ub bg_color, double radius,
00856 const std::string &layer_id, double opacity)
00857 {
00858
00859 LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id));
00860 if (am_it == layer_map_.end ())
00861 {
00862 PCL_DEBUG ("[pcl::visualization::ImageViewer::markPoint] No layer with ID='%s' found. Creating new one...\n", layer_id.c_str ());
00863 am_it = createLayer (layer_id, getSize ()[0] - 1, getSize ()[1] - 1, opacity, false);
00864 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION > 10))
00865 interactor_style_->adjustCamera (ren_);
00866 #endif
00867 }
00868
00869 vtkSmartPointer<context_items::Point> point = vtkSmartPointer<context_items::Point>::New ();
00870 point->setColors (fg_color[0], fg_color[1], fg_color[2]);
00871 point->setOpacity (opacity);
00872
00873 vtkSmartPointer<context_items::Disk> disk = vtkSmartPointer<context_items::Disk>::New ();
00874 disk->setColors (bg_color[0], bg_color[1], bg_color[2]);
00875 disk->setOpacity (opacity);
00876
00877 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION > 10))
00878 point->set (static_cast<float> (u), static_cast<float> (v));
00879 disk->set (static_cast<float> (u), static_cast<float> (v), static_cast<float> (radius));
00880 #else
00881 point->set (static_cast<float> (u), static_cast<float> (getSize ()[1] - v));
00882 disk->set (static_cast<float> (u), static_cast<float> (getSize ()[1] - v), static_cast<float> (radius));
00883 #endif
00884
00885 am_it->actor->GetScene ()->AddItem (disk);
00886 am_it->actor->GetScene ()->AddItem (point);
00887 }
00888
00890 void
00891 pcl::visualization::ImageViewer::render ()
00892 {
00893 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 10))
00894 image_viewer_->Render ();
00895 #else
00896 win_->Render ();
00897 #endif
00898 for(unsigned int i = 0; i < image_data_.size(); i++)
00899 delete [] image_data_[i];
00900 image_data_.clear ();
00901 }
00902
00904 void
00905 pcl::visualization::ImageViewer::convertIntensityCloudToUChar (
00906 const pcl::PointCloud<pcl::Intensity> &cloud,
00907 boost::shared_array<unsigned char> data)
00908 {
00909 int j = 0;
00910 for (size_t i = 0; i < cloud.points.size (); ++i)
00911 {
00912 data[j++] = static_cast <unsigned char> (cloud.points[i].intensity * 255);
00913 }
00914 }
00915
00917 void
00918 pcl::visualization::ImageViewer::convertIntensityCloud8uToUChar (
00919 const pcl::PointCloud<pcl::Intensity8u> &cloud,
00920 boost::shared_array<unsigned char> data)
00921 {
00922 int j = 0;
00923 for (size_t i = 0; i < cloud.points.size (); ++i)
00924 data[j++] = static_cast<unsigned char> (cloud.points[i].intensity);
00925 }
00926
00930 pcl::visualization::ImageViewerInteractorStyle::ImageViewerInteractorStyle ()
00931 {
00932 }
00933
00935 void
00936 pcl::visualization::ImageViewerInteractorStyle::OnChar ()
00937 {
00938 FindPokedRenderer (Interactor->GetEventPosition ()[0], Interactor->GetEventPosition ()[1]);
00939
00940 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION > 10))
00941 vtkPropCollection *props = CurrentRenderer->GetViewProps ();
00942 vtkProp *prop = 0;
00943 vtkAssemblyPath *path;
00944 vtkImageSlice *image_prop = 0;
00945 vtkCollectionSimpleIterator pit;
00946
00947 for (props->InitTraversal (pit); (prop = props->GetNextProp (pit)); )
00948 {
00949 for (prop->InitPathTraversal (); (path = prop->GetNextPath ()); )
00950 {
00951 vtkProp *try_prop = path->GetLastNode ()->GetViewProp ();
00952 if ( (image_prop = vtkImageSlice::SafeDownCast (try_prop)) != 0 )
00953 break;
00954 }
00955 }
00956
00957 vtkImageProperty *property = image_prop->GetProperty ();
00958 #endif
00959
00960 switch (Interactor->GetKeyCode ())
00961 {
00962 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION > 10))
00963 case 'r':
00964 case 'R':
00965 property->SetColorLevel (127.5);
00966 property->SetColorWindow (255);
00967 this->Interactor->Render ();
00968 break;
00969 #endif
00970 default:
00971 Superclass::OnChar ();
00972 break;
00973 }
00974 }
00975
00977 void
00978 pcl::visualization::ImageViewerInteractorStyle::adjustCamera (
00979 vtkImageData *image, vtkRenderer *ren)
00980 {
00981
00982 double origin[3], spacing[3];
00983 int extent[6];
00984 image->GetOrigin (origin);
00985 image->GetSpacing (spacing);
00986 image->GetExtent (extent);
00987
00988 vtkCamera* camera = ren->GetActiveCamera ();
00989 double xc = origin[0] + 0.5 * (extent[0] + extent[1]) * spacing[0];
00990 double yc = origin[1] + 0.5 * (extent[2] + extent[3]) * spacing[1];
00991 double yd = (extent[3] - extent[2] + 1) * spacing[1];
00992 double d = camera->GetDistance ();
00993 camera->SetParallelScale (0.5 * yd);
00994 camera->SetFocalPoint (xc, yc, 0.0);
00995 camera->SetPosition (xc, yc, d);
00996 }
00997
00999 void
01000 pcl::visualization::ImageViewerInteractorStyle::adjustCamera (vtkRenderer *ren)
01001 {
01002
01003 vtkCamera* camera = ren->GetActiveCamera ();
01004 int *wh = ren->GetRenderWindow ()->GetSize ();
01005 double xc = static_cast<double> (wh[0]) / 2.0,
01006 yc = static_cast<double> (wh[1]) / 2.0,
01007 yd = static_cast<double> (wh[1]),
01008 d = 3.346065;
01009 camera->SetParallelScale (0.5 * yd);
01010 camera->SetFocalPoint (xc, yc, 0.0);
01011 camera->SetPosition (xc, yc, d);
01012 }
01013
01015 void
01016 pcl::visualization::ImageViewerInteractorStyle::OnLeftButtonDown ()
01017 {
01018 int x = Interactor->GetEventPosition ()[0];
01019 int y = Interactor->GetEventPosition ()[1];
01020
01021 FindPokedRenderer (x, y);
01022 if (CurrentRenderer == NULL)
01023 return;
01024
01025
01026 GrabFocus (this->EventCallbackCommand);
01027
01028 if (!this->Interactor->GetShiftKey() && !this->Interactor->GetControlKey())
01029 {
01030 WindowLevelStartPosition[0] = x;
01031 WindowLevelStartPosition[1] = y;
01032 StartWindowLevel ();
01033 }
01034 else if (Interactor->GetShiftKey ())
01035 return;
01036
01037 else if (Interactor->GetControlKey ())
01038 return;
01039
01040 else
01041 Superclass::OnLeftButtonDown ();
01042 }
01043
01045 void
01046 pcl::visualization::ImageViewer::setWindowTitle (const std::string& name)
01047 {
01048 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION >= 10))
01049 win_->SetWindowName (name.c_str ());
01050 #else
01051 image_viewer_->GetRenderWindow ()->SetWindowName (name.c_str ());
01052 #endif
01053 }
01054
01056 void
01057 pcl::visualization::ImageViewer::setPosition (int x, int y)
01058 {
01059 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION >= 10))
01060 win_->SetPosition (x, y);
01061 #else
01062 image_viewer_->GetRenderWindow ()->SetPosition (x, y);
01063 #endif
01064 }
01065
01067 int*
01068 pcl::visualization::ImageViewer::getSize ()
01069 {
01070 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION >= 10))
01071 return (win_->GetSize ());
01072 #else
01073 return (image_viewer_->GetRenderWindow ()->GetSize ());
01074 #endif
01075 }
01076
01078 void
01079 pcl::visualization::ImageViewer::setSize (int xw, int yw)
01080 {
01081 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION >= 10))
01082 win_->SetSize (xw, yw);
01083 #else
01084 image_viewer_->GetRenderWindow ()->SetSize (xw, yw);
01085 #endif
01086 }
01087
01089 namespace pcl
01090 {
01091 namespace visualization
01092 {
01093 vtkStandardNewMacro (ImageViewerInteractorStyle);
01094 }
01095 }
01096