render_points_test.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 "test/render_points_test.h"
00031 
00032 #include <QMouseEvent>
00033 #include <QWheelEvent>
00034 #include <QApplication>
00035 #include <QVBoxLayout>
00036 
00037 using namespace rviz;
00038 
00039 MyFrame::MyFrame( QWidget* parent )
00040   : QWidget(parent)
00041   , left_mouse_down_( false )
00042   , middle_mouse_down_( false )
00043   , right_mouse_down_( false )
00044   , mouse_x_( 0 )
00045   , mouse_y_( 0 )
00046 {
00047   render_system_ = RenderSystem::get();
00048   root_ = render_system_->root();
00049 
00050   try
00051   {
00052     scene_manager_ = root_->createSceneManager( Ogre::ST_GENERIC, "TestSceneManager" );
00053 
00054     render_panel_ = new QtOgreRenderWindow();
00055     render_panel_->resize( this->size() );
00056     render_panel_->setAutoRender(false);
00057 
00058     QVBoxLayout* layout = new QVBoxLayout;
00059     layout->setContentsMargins( 0, 0, 0, 0 );
00060     layout->addWidget( render_panel_ );
00061     setLayout( layout );
00062 
00063     camera_ = new OrbitCamera( scene_manager_ );
00064     camera_->setPosition( 0, 0, 15 );
00065     camera_->getOgreCamera()->setNearClipDistance( 0.1 );
00066 
00067     render_panel_->setCamera( camera_->getOgreCamera() );
00068     render_panel_->setBackgroundColor( Ogre::ColourValue( 0.8,0.8,1 ) );
00069 
00070     Ogre::Light* directional_light = scene_manager_->createLight( "MainDirectional" );
00071     directional_light->setType( Ogre::Light::LT_DIRECTIONAL );
00072     directional_light->setDirection( Ogre::Vector3( 0, -1, 1 ) );
00073     directional_light->setDiffuseColour( Ogre::ColourValue( 1.0f, 1.0f, 1.0f ) );
00074 
00075 #if 0
00076     Grid* grid = new Grid( scene_manager_, NULL, Grid::Lines, 10, 1.0f, 0.02, Ogre::ColourValue(1.0f, 1.0f, 1.0f, 0.5f));
00077     grid->setHeight(4);
00078 
00079 
00080     BillboardLine* line = new BillboardLine( scene_manager_, NULL );
00081     line->setMaxPointsPerLine(105);
00082     for ( int i = -50; i < 50; ++i )
00083       {
00084         line->addPoint( Ogre::Vector3( i*2, 0.0f, -1.0f ) );
00085       }
00086 
00087     for ( int i = 0; i < 5; ++i )
00088       {
00089         line->addPoint( Ogre::Vector3( 4.0f, 0.0f, i ) );
00090       }
00091 
00092     line->setLineWidth( 0.05 );
00093     line->setColor( 0.0f, 1.0f, 0.0f, 0.5f );
00094 
00095     Shape* sphere = new Shape(Shape::Sphere, scene_manager_);
00096     sphere->setPosition(Ogre::Vector3(0.0f, 0.0f, 2.0f));
00097     sphere->setColor(0.0f, 1.0f, 2.0f, 1.0f);
00098     Shape* cube = new Shape(Shape::Cube, scene_manager_);
00099     cube->setPosition(Ogre::Vector3(0.0f, 1.0f, 2.0f));
00100     cube->setColor(1.0f, 0.0f, 0.0f, 1.0f);
00101     Shape* cylinder = new Shape(Shape::Cylinder, scene_manager_);
00102     cylinder->setPosition(Ogre::Vector3(0.0f, 2.0f, 2.0f));
00103     cylinder->setColor(1.0f, 1.0f, 0.0f, 1.0f);
00104     Shape* cone = new Shape(Shape::Cone, scene_manager_);
00105     cone->setPosition(Ogre::Vector3(0.0f, 3.0f, 2.0f));
00106     cone->setColor(0.0f, 0.0f, 1.0f, 1.0f);
00107 
00108     Axes* axes = new Axes( scene_manager_ );
00109     //axes->setScale( Ogre::Vector3( 2.0f, 2.0f, 2.0f ) );
00110 
00111     /*Cone* cone = new Cone( scene_manager_, NULL );
00112       cone->setScale( Ogre::Vector3( 0.3f, 2.0f, 0.3f ) );*/
00113 
00114     Arrow* arrow = new Arrow( scene_manager_ );
00115     arrow->setHeadColor( 1.0f, 0.0f, 0.0f );
00116     arrow->setShaftColor( 0.0f, 0.0f, 1.0f );
00117     arrow->setOrientation( Ogre::Quaternion::IDENTITY );
00118     //arrow->setOrientation( Ogre::Quaternion( Ogre::Degree( 45 ), Ogre::Vector3::UNIT_X ) );
00119     //arrow->setScale( Ogre::Vector3( 1.0f, 1.0f, 3.0f ) );
00120 #endif
00121 
00122 #if 01
00123     Ogre::SceneNode* scene_node = scene_manager_->getRootSceneNode()->createChildSceneNode();
00124     PointCloud* pointCloud = new PointCloud();
00125     pointCloud->setDimensions(0.05f, 0.05f, 0.05f);
00126     //pointCloud->setColorByIndex(true);
00127     pointCloud->setRenderMode(PointCloud::RM_SQUARES);
00128     pointCloud->setCommonDirection(Ogre::Vector3(0.0, 1.0, 0.0));
00129     pointCloud->setCommonUpVector(Ogre::Vector3(0.0, 0.0, -1.0));
00130     pointCloud->setAlpha(1.0);
00131     std::vector<PointCloud::Point> points;
00132     int32_t xcount = 200;
00133     int32_t ycount = 100;
00134     int32_t zcount = 100;
00135     //        points.resize(xcount * ycount * zcount);
00136     float factor = 0.1f;
00137     for (int32_t x = 0; x < xcount; ++x)
00138     {
00139       for (int32_t y = 0; y < ycount; ++y)
00140       {
00141         for (int32_t z = 0; z < zcount; ++z)
00142         {
00143           //    int32_t index = (ycount*zcount*x) + zcount*y + z;
00144           PointCloud::Point point;// = points[index];
00145           point.position.x = x * factor;
00146           point.position.y = y * factor;
00147           point.position.z = z * factor;
00148 
00149           point.setColor(x * 0.1, y * 0.1, z * 0.1);
00150           points.push_back(point);
00151         }
00152       }
00153     }
00154 
00155     printf("size: %d\n", (int)points.size());
00156     pointCloud->addPoints( &points.front(), points.size() );
00157     scene_node->attachObject(pointCloud);
00158 #endif
00159   }
00160   catch ( Ogre::Exception& e )
00161   {
00162     printf( "Fatal error: %s\n", e.what() );
00163     exit(1);
00164   }
00165 
00166   connect( &render_timer_, SIGNAL( timeout() ), this, SLOT( doRender() ));
00167   render_timer_.start(33);
00168 }
00169 
00170 MyFrame::~MyFrame()
00171 {
00172 }
00173 
00174 void MyFrame::doRender()
00175 {
00176   ros::WallTime start = ros::WallTime::now();
00177   root_->renderOneFrame();
00178   ros::WallTime end = ros::WallTime::now();
00179   printf("Render took [%f] msec\n", (end - start).toSec() * 1000.0f);
00180 }
00181 
00182 void MyFrame::mousePressEvent( QMouseEvent* event )
00183 {
00184   left_mouse_down_ = false;
00185   middle_mouse_down_ = false;
00186   right_mouse_down_ = false;
00187 
00188   switch( event->button() )
00189   {
00190   case Qt::LeftButton:
00191     left_mouse_down_ = true;
00192     break;
00193   case Qt::MidButton:
00194     middle_mouse_down_ = true;
00195     break;
00196   case Qt::RightButton:
00197     right_mouse_down_ = true;
00198     break;
00199   default:
00200     break;
00201   }
00202 }
00203 
00204 void MyFrame::mouseReleaseEvent( QMouseEvent* event )
00205 {
00206   switch( event->button() )
00207   {
00208   case Qt::LeftButton:
00209     left_mouse_down_ = false;
00210     break;
00211   case Qt::MidButton:
00212     middle_mouse_down_ = false;
00213     break;
00214   case Qt::RightButton:
00215     right_mouse_down_ = false;
00216     break;
00217   default:
00218     break;
00219   }
00220 }
00221 
00222 void MyFrame::mouseMoveEvent( QMouseEvent* event )
00223 {
00224   int32_t diff_x = event->x() - mouse_x_;
00225   int32_t diff_y = event->y() - mouse_y_;
00226 
00227   mouse_x_ = event->x();
00228   mouse_y_ = event->y();
00229 
00230   bool cmd = event->modifiers() & Qt::ControlModifier;
00231   bool shift = event->modifiers() & Qt::ShiftModifier;
00232   bool alt = event->modifiers() & Qt::AltModifier;
00233 
00234   if ( left_mouse_down_ )
00235   {
00236     camera_->mouseLeftDrag( diff_x, diff_y, cmd, alt, shift );
00237   }
00238   else if ( middle_mouse_down_ )
00239   {
00240     camera_->mouseMiddleDrag( diff_x, diff_y, cmd, alt, shift );
00241   }
00242   else if ( right_mouse_down_ )
00243   {
00244     camera_->mouseRightDrag( diff_x, diff_y, cmd, alt, shift );
00245   }
00246 }
00247 
00248 void MyFrame::wheelEvent( QWheelEvent* event )
00249 {
00250   if( event->delta() != 0 )
00251   {
00252     bool cmd = event->modifiers() & Qt::ControlModifier;
00253     bool shift = event->modifiers() & Qt::ShiftModifier;
00254     bool alt = event->modifiers() & Qt::AltModifier;
00255 
00256     camera_->scrollWheel( event->delta(), cmd, alt, shift );
00257   }
00258 }
00259 
00260 int main( int argc, char** argv )
00261 {
00262   QApplication app( argc, argv );
00263 
00264   MyFrame frame;
00265   frame.resize( 800, 600 );
00266   frame.setWindowTitle( "I hope this is not all black." );
00267   frame.show();
00268 
00269   return app.exec();
00270 }


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Thu Aug 27 2015 15:02:28