render_panel.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <QApplication>
00031 #include <QMenu>
00032 
00033 #include "render_panel.h"
00034 #include "visualization_manager.h"
00035 #include "display.h"
00036 #include "display_wrapper.h"
00037 #include "tools/tool.h"
00038 #include "viewport_mouse_event.h"
00039 #include "view_controller.h"
00040 
00041 #include <OGRE/OgreRoot.h>
00042 #include <OGRE/OgreViewport.h>
00043 
00044 namespace rviz
00045 {
00046 
00047 RenderPanel::RenderPanel( ogre_tools::RenderSystem* render_system, Display* display, QWidget* parent )
00048   : QtOgreRenderWindow( render_system, parent )
00049   , mouse_x_( 0 )
00050   , mouse_y_( 0 )
00051   , manager_( 0 )
00052   , scene_manager_( 0 )
00053   , camera_( 0 )
00054   , view_controller_( 0 )
00055   , display_( display )
00056 {
00057   setFocus( Qt::OtherFocusReason );
00058 }
00059 
00060 RenderPanel::~RenderPanel()
00061 {
00062   delete view_controller_;
00063   scene_manager_->destroyCamera(camera_);
00064 }
00065 
00066 void RenderPanel::initialize(Ogre::SceneManager* scene_manager, VisualizationManager* manager)
00067 {
00068   manager_ = manager;
00069   scene_manager_ = scene_manager;
00070 
00071   std::stringstream ss;
00072   static int count = 0;
00073   ss << "RenderPanelCamera" << count++;
00074   camera_ = scene_manager_->createCamera(ss.str());
00075 
00076   setCamera( camera_ );
00077 }
00078 
00079 void RenderPanel::onRenderWindowMouseEvents( QMouseEvent* event )
00080 {
00081   int last_x = mouse_x_;
00082   int last_y = mouse_y_;
00083 
00084   mouse_x_ = event->x();
00085   mouse_y_ = event->y();
00086 
00087   if (manager_)
00088   {
00089     setFocus( Qt::MouseFocusReason );
00090 
00091     ViewportMouseEvent vme(this, getViewport(), event, last_x, last_y);
00092     manager_->handleMouseEvent(vme);
00093     event->accept();
00094   }
00095 }
00096 
00097 void RenderPanel::wheelEvent( QWheelEvent* event )
00098 {
00099   int last_x = mouse_x_;
00100   int last_y = mouse_y_;
00101 
00102   mouse_x_ = event->x();
00103   mouse_y_ = event->y();
00104 
00105   if (manager_)
00106   {
00107     setFocus( Qt::MouseFocusReason );
00108 
00109     ViewportMouseEvent vme(this, getViewport(), event, last_x, last_y);
00110     manager_->handleMouseEvent(vme);
00111     event->accept();
00112   }
00113 }
00114 
00115 void RenderPanel::keyPressEvent( QKeyEvent* event )
00116 {
00117   if( manager_ )
00118   {
00119     manager_->handleChar( event );
00120   }
00121 }
00122 
00123 void RenderPanel::setViewController(ViewController* controller)
00124 {
00125   if (view_controller_)
00126   {
00127     view_controller_->deactivate();
00128   }
00129 
00130   delete view_controller_;
00131   view_controller_ = controller;
00132 
00133   view_controller_->activate(camera_, manager_ ? manager_->getTargetFrame() : "");
00134 }
00135 
00136 void RenderPanel::showContextMenu( boost::shared_ptr<QMenu> menu )
00137 {
00138   boost::mutex::scoped_lock lock(context_menu_mutex_);
00139   context_menu_ = menu;
00140 
00141   QApplication::postEvent( this, new QContextMenuEvent( QContextMenuEvent::Mouse, QPoint() ));
00142 }
00143 
00144 void RenderPanel::contextMenuEvent( QContextMenuEvent* event )
00145 {
00146   boost::shared_ptr<QMenu> context_menu;
00147   {
00148     boost::mutex::scoped_lock lock(context_menu_mutex_);
00149     context_menu.swap(context_menu_);
00150   }
00151 
00152   if ( context_menu )
00153   {
00154     context_menu->exec( QCursor::pos() );
00155   }
00156 }
00157 
00158 } // namespace rviz


rviz_qt
Author(s): Dave Hershberger
autogenerated on Fri Dec 6 2013 20:56:53