render_window.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2012, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of Willow Garage, Inc. nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  */
00036 
00037 #include <pcl/apps/modeler/render_window.h>
00038 #include <pcl/apps/modeler/render_window_item.h>
00039 #include <pcl/apps/modeler/scene_tree.h>
00040 #include <pcl/apps/modeler/dock_widget.h>
00041 #include <pcl/apps/modeler/main_window.h>
00042 #include <vtkProp.h>
00043 #include <vtkRenderer.h>
00044 #include <vtkBoundingBox.h>
00045 #include <vtkSmartPointer.h>
00046 #include <vtkRenderWindow.h>
00047 #include <vtkCubeAxesActor.h>
00048 #include <vtkRendererCollection.h>
00049 
00050 
00052 pcl::modeler::RenderWindow::RenderWindow(RenderWindowItem* render_window_item, QWidget *parent, Qt::WFlags flags)
00053   : QVTKWidget(parent, flags),
00054   axes_(vtkSmartPointer<vtkCubeAxesActor>::New()),
00055   render_window_item_(render_window_item)
00056 {
00057   setFocusPolicy(Qt::StrongFocus);
00058   initRenderer();
00059   updateAxes();
00060   setShowAxes(true);
00061 }
00062 
00064 pcl::modeler::RenderWindow::~RenderWindow()
00065 {
00066   DockWidget* dock_widget = dynamic_cast<DockWidget*>(parent());
00067   if (dock_widget != NULL)
00068   {
00069     MainWindow::getInstance().removeDockWidget(dock_widget);
00070     dock_widget->deleteLater();
00071   }
00072 
00073   return;
00074 }
00075 
00077 void
00078 pcl::modeler::RenderWindow::initRenderer()
00079 {
00080   vtkSmartPointer<vtkRenderWindow> win = GetRenderWindow();
00081   vtkSmartPointer<vtkRenderer> renderer = vtkSmartPointer<vtkRenderer>::New();
00082   win->AddRenderer(renderer);
00083 
00084   // FPS callback
00085   //vtkSmartPointer<vtkTextActor> txt = vtkSmartPointer<vtkTextActor>::New ();
00086   //typedef pcl::visualization::FPSCallback FPSCallback;
00087   //vtkSmartPointer<FPSCallback> update_fps = vtkSmartPointer<FPSCallback>::New ();
00088   //update_fps->setTextActor (txt);
00089   //renderer->AddObserver (vtkCommand::EndEvent, update_fps);
00090   //renderer->AddActor (txt);
00091 
00092   // Set up render window
00093   win->AlphaBitPlanesOff ();
00094   win->PointSmoothingOff ();
00095   win->LineSmoothingOff ();
00096   win->PolygonSmoothingOff ();
00097   win->SwapBuffersOn ();
00098   win->SetStereoTypeToAnaglyph ();
00099   win->GetInteractor()->SetDesiredUpdateRate (30.0);
00100 
00101   return;
00102 }
00103 
00105 void
00106 pcl::modeler::RenderWindow::focusInEvent(QFocusEvent * event)
00107 {
00108   dynamic_cast<SceneTree*>(render_window_item_->treeWidget())->selectRenderWindowItem(render_window_item_);
00109 
00110   QVTKWidget::focusInEvent(event);
00111 }
00112 
00114 void
00115 pcl::modeler::RenderWindow::setActive(bool flag)
00116 {
00117   DockWidget* dock_widget = dynamic_cast<DockWidget*>(parent());
00118   if (dock_widget != NULL)
00119     dock_widget->setFocusBasedStyle(flag);
00120 
00121   return;
00122 }
00123 
00125 void
00126 pcl::modeler::RenderWindow::setTitle(const QString& title)
00127 {
00128   DockWidget* dock_widget = dynamic_cast<DockWidget*>(parent());
00129   if (dock_widget != NULL)
00130     dock_widget->setWindowTitle(title);
00131 
00132   return;
00133 }
00134 
00136 void
00137 pcl::modeler::RenderWindow::render()
00138 {
00139   GetRenderWindow()->Render();
00140 }
00141 
00143 void
00144 pcl::modeler::RenderWindow::resetCamera()
00145 {
00146   double bounds[6];
00147   GetRenderWindow()->GetRenderers()->GetFirstRenderer()->ComputeVisiblePropBounds(bounds);
00148   GetRenderWindow()->GetRenderers()->GetFirstRenderer()->ResetCamera(bounds);
00149   render();
00150 }
00151 
00153 void
00154 pcl::modeler::RenderWindow::getBackground(double& r, double& g, double& b)
00155 {
00156   GetRenderWindow()->GetRenderers()->GetFirstRenderer()->GetBackground(r, g, b);
00157 }
00158 
00160 void
00161 pcl::modeler::RenderWindow::setBackground(double r, double g, double b)
00162 {
00163   GetRenderWindow()->GetRenderers()->GetFirstRenderer()->SetBackground(r, g, b);
00164 }
00165 
00166 
00168 void
00169 pcl::modeler::RenderWindow::updateAxes()
00170 {
00171   vtkBoundingBox bb;
00172 
00173   vtkActorCollection* actors = GetRenderWindow()->GetRenderers()->GetFirstRenderer()->GetActors();
00174 
00175   actors->InitTraversal();
00176   for (int i = 0, i_end = actors->GetNumberOfItems(); i < i_end; ++ i)
00177   {
00178     vtkActor* actor = actors->GetNextActor();
00179     if (actor == axes_.GetPointer())
00180       continue;
00181 
00182     double actor_bounds[6];
00183     actor->GetBounds(actor_bounds);
00184     bb.AddBounds(actor_bounds);
00185   }
00186 
00187   double bounds[6];
00188   bb.GetBounds(bounds);
00189   axes_->SetBounds(bounds);
00190   axes_->SetCamera(GetRenderWindow()->GetRenderers()->GetFirstRenderer()->GetActiveCamera());
00191 }
00192 
00194 void
00195 pcl::modeler::RenderWindow::setShowAxes(bool flag)
00196 {
00197   if (flag)
00198     GetRenderWindow()->GetRenderers()->GetFirstRenderer()->AddActor(axes_);
00199   else
00200     GetRenderWindow()->GetRenderers()->GetFirstRenderer()->RemoveActor(axes_);
00201 
00202   return;
00203 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:32:08