point_cloud.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 "point_cloud.h"
00031 #include <ros/assert.h>
00032 
00033 #include <OGRE/OgreSceneManager.h>
00034 #include <OGRE/OgreSceneNode.h>
00035 #include <OGRE/OgreVector3.h>
00036 #include <OGRE/OgreQuaternion.h>
00037 #include <OGRE/OgreManualObject.h>
00038 #include <OGRE/OgreMaterialManager.h>
00039 #include <OGRE/OgreBillboardSet.h>
00040 #include <OGRE/OgreBillboard.h>
00041 #include <OGRE/OgreTexture.h>
00042 #include <OGRE/OgreTextureManager.h>
00043 
00044 #include <sstream>
00045 
00046 #include "rviz/ogre_helpers/custom_parameter_indices.h"
00047 #include "rviz/selection/forwards.h"
00048 
00049 #define VERTEX_BUFFER_CAPACITY (36 * 1024 * 10)
00050 
00051 namespace rviz
00052 {
00053 
00054 static float g_point_vertices[3] =
00055 {
00056   0.0f, 0.0f, 0.0f
00057 };
00058 
00059 static float g_billboard_vertices[6*3] =
00060 {
00061   -0.5f, 0.5f, 0.0f,
00062   -0.5f, -0.5f, 0.0f,
00063   0.5f, 0.5f, 0.0f,
00064   0.5f, 0.5f, 0.0f,
00065   -0.5f, -0.5f, 0.0f,
00066   0.5f, -0.5f, 0.0f,
00067 };
00068 
00069 static float g_billboard_sphere_vertices[3*3] =
00070 {
00071   0.0f, 1.0f, 0.0f,
00072   -0.866025404f, -0.5f, 0.0f,
00073   0.866025404f, -0.5f, 0.0f,
00074 };
00075 
00076 static float g_box_vertices[6*6*3] =
00077 {
00078   // front
00079   -0.5f, 0.5f, -0.5f,
00080   -0.5f, -0.5f, -0.5f,
00081   0.5f, 0.5f, -0.5f,
00082   0.5f, 0.5f, -0.5f,
00083   -0.5f, -0.5f, -0.5f,
00084   0.5f, -0.5f, -0.5f,
00085 
00086   // back
00087   -0.5f, 0.5f, 0.5f,
00088   0.5f, 0.5f, 0.5f,
00089   -0.5f, -0.5f, 0.5f,
00090   0.5f, 0.5f, 0.5f,
00091   0.5f, -0.5f, 0.5f,
00092   -0.5f, -0.5f, 0.5f,
00093 
00094   // right
00095   0.5, 0.5, 0.5,
00096   0.5, 0.5, -0.5,
00097   0.5, -0.5, 0.5,
00098   0.5, 0.5, -0.5,
00099   0.5, -0.5, -0.5,
00100   0.5, -0.5, 0.5,
00101 
00102   // left
00103   -0.5, 0.5, 0.5,
00104   -0.5, -0.5, 0.5,
00105   -0.5, 0.5, -0.5,
00106   -0.5, 0.5, -0.5,
00107   -0.5, -0.5, 0.5,
00108   -0.5, -0.5, -0.5,
00109 
00110   // top
00111   -0.5, 0.5, -0.5,
00112   0.5, 0.5, -0.5,
00113   -0.5, 0.5, 0.5,
00114   0.5, 0.5, -0.5,
00115   0.5, 0.5, 0.5,
00116   -0.5, 0.5, 0.5,
00117 
00118   // bottom
00119   -0.5, -0.5, -0.5,
00120   -0.5, -0.5, 0.5,
00121   0.5, -0.5, -0.5,
00122   0.5, -0.5, -0.5,
00123   -0.5, -0.5, 0.5,
00124   0.5, -0.5, 0.5,
00125 };
00126 
00127 Ogre::String PointCloud::sm_Type = "PointCloud";
00128 
00129 PointCloud::PointCloud()
00130 : bounding_radius_( 0.0f )
00131 , point_count_( 0 )
00132 , common_direction_( Ogre::Vector3::NEGATIVE_UNIT_Z )
00133 , common_up_vector_( Ogre::Vector3::UNIT_Y )
00134 , color_by_index_(false)
00135 , current_mode_supports_geometry_shader_(false)
00136 {
00137   std::stringstream ss;
00138   static int count = 0;
00139   ss << "PointCloudMaterial" << count++;
00140   point_material_ = Ogre::MaterialManager::getSingleton().getByName("rviz/PointCloudPoint");
00141   square_material_ = Ogre::MaterialManager::getSingleton().getByName("rviz/PointCloudSquare");
00142   flat_square_material_ = Ogre::MaterialManager::getSingleton().getByName("rviz/PointCloudFlatSquare");
00143   sphere_material_ = Ogre::MaterialManager::getSingleton().getByName("rviz/PointCloudSphere");
00144   tile_material_ = Ogre::MaterialManager::getSingleton().getByName("rviz/PointCloudTile");
00145   box_material_ = Ogre::MaterialManager::getSingleton().getByName("rviz/PointCloudBox");
00146 
00147   point_material_ = Ogre::MaterialPtr(point_material_)->clone(ss.str() + "Point");
00148   square_material_ = Ogre::MaterialPtr(square_material_)->clone(ss.str() + "Square");
00149   flat_square_material_ = Ogre::MaterialPtr(flat_square_material_)->clone(ss.str() + "FlatSquare");
00150   sphere_material_ = Ogre::MaterialPtr(sphere_material_)->clone(ss.str() + "Sphere");
00151   tile_material_ = Ogre::MaterialPtr(tile_material_)->clone(ss.str() + "Tiles");
00152   box_material_ = Ogre::MaterialPtr(box_material_)->clone(ss.str() + "Box");
00153 
00154   point_material_->load();
00155   square_material_->load();
00156   flat_square_material_->load();
00157   sphere_material_->load();
00158   tile_material_->load();
00159   box_material_->load();
00160 
00161   setAlpha( 1.0f );
00162   setRenderMode(RM_SPHERES);
00163   setDimensions(0.01f, 0.01f, 0.01f);
00164 
00165   clear();
00166 }
00167 
00168 PointCloud::~PointCloud()
00169 {
00170   clear();
00171 
00172   point_material_->unload();
00173   square_material_->unload();
00174   flat_square_material_->unload();
00175   sphere_material_->unload();
00176   tile_material_->unload();
00177   box_material_->unload();
00178 
00179   Ogre::MaterialManager::getSingleton().remove(point_material_);
00180   Ogre::MaterialManager::getSingleton().remove(square_material_);
00181   Ogre::MaterialManager::getSingleton().remove(flat_square_material_);
00182   Ogre::MaterialManager::getSingleton().remove(sphere_material_);
00183   Ogre::MaterialManager::getSingleton().remove(tile_material_);
00184   Ogre::MaterialManager::getSingleton().remove(box_material_);
00185 }
00186 
00187 const Ogre::AxisAlignedBox& PointCloud::getBoundingBox() const
00188 {
00189   return bounding_box_;
00190 }
00191 
00192 float PointCloud::getBoundingRadius() const
00193 {
00194   return bounding_radius_;
00195 }
00196 
00197 void PointCloud::getWorldTransforms(Ogre::Matrix4* xform) const
00198 {
00199   *xform = _getParentNodeFullTransform();
00200 }
00201 
00202 void PointCloud::clear()
00203 {
00204   point_count_ = 0;
00205   bounding_box_.setNull();
00206   bounding_radius_ = 0.0f;
00207 
00208   if (getParentSceneNode())
00209   {
00210     V_PointCloudRenderable::iterator it = renderables_.begin();
00211     V_PointCloudRenderable::iterator end = renderables_.end();
00212     for (; it != end; ++it)
00213     {
00214       getParentSceneNode()->detachObject(it->get());
00215     }
00216     getParentSceneNode()->needUpdate();
00217   }
00218 
00219   renderables_.clear();
00220 }
00221 
00222 void PointCloud::regenerateAll()
00223 {
00224   if (point_count_ == 0)
00225   {
00226     return;
00227   }
00228 
00229   V_Point points;
00230   points.swap(points_);
00231   uint32_t count = point_count_;
00232 
00233   clear();
00234 
00235   addPoints(&points.front(), count);
00236 }
00237 
00238 void PointCloud::setColorByIndex(bool set)
00239 {
00240   color_by_index_ = set;
00241   regenerateAll();
00242 }
00243 
00244 void PointCloud::setHighlightColor( float r, float g, float b )
00245 {
00246   Ogre::Vector4 highlight( r, g, b, 0.0f );
00247 
00248   V_PointCloudRenderable::iterator it = renderables_.begin();
00249   V_PointCloudRenderable::iterator end = renderables_.end();
00250   for (; it != end; ++it)
00251   {
00252     (*it)->setCustomParameter(HIGHLIGHT_PARAMETER, highlight);
00253   }
00254 }
00255 
00256 void PointCloud::setRenderMode(RenderMode mode)
00257 {
00258   render_mode_ = mode;
00259 
00260   if (mode == RM_POINTS)
00261   {
00262     current_material_ = Ogre::MaterialPtr(point_material_);
00263   }
00264   else if (mode == RM_SQUARES)
00265   {
00266     current_material_ = Ogre::MaterialPtr(square_material_);
00267   }
00268   else if (mode == RM_FLAT_SQUARES)
00269   {
00270     current_material_ = Ogre::MaterialPtr(flat_square_material_);
00271   }
00272   else if (mode == RM_SPHERES)
00273   {
00274     current_material_ = Ogre::MaterialPtr(sphere_material_);
00275   }
00276   else if (mode == RM_TILES)
00277   {
00278     current_material_ = Ogre::MaterialPtr(tile_material_);
00279   }
00280   else if (mode == RM_BOXES)
00281   {
00282     current_material_ = Ogre::MaterialPtr(box_material_);
00283   }
00284 
00285   current_material_->load();
00286 
00287   //ROS_INFO("Best technique [%s] [gp=%s]", current_material_->getBestTechnique()->getName().c_str(), current_material_->getBestTechnique()->getPass(0)->getGeometryProgramName().c_str());
00288 
00289   bool geom_support_changed = false;
00290   Ogre::Technique* best = current_material_->getBestTechnique();
00291   if (best)
00292   {
00293     if (current_material_->getBestTechnique()->getName() == "gp")
00294     {
00295       if (!current_mode_supports_geometry_shader_)
00296       {
00297         geom_support_changed = true;
00298       }
00299 
00300       current_mode_supports_geometry_shader_ = true;
00301 
00302       //ROS_INFO("Using geometry shader");
00303     }
00304     else
00305     {
00306       if (current_mode_supports_geometry_shader_)
00307       {
00308         geom_support_changed = true;
00309       }
00310 
00311       current_mode_supports_geometry_shader_ = false;
00312     }
00313   }
00314   else
00315   {
00316     geom_support_changed = true;
00317     current_mode_supports_geometry_shader_ = false;
00318 
00319     ROS_ERROR("No techniques available for material [%s]", current_material_->getName().c_str());
00320   }
00321 
00322   if (geom_support_changed)
00323   {
00324     renderables_.clear();
00325   }
00326 
00327   V_PointCloudRenderable::iterator it = renderables_.begin();
00328   V_PointCloudRenderable::iterator end = renderables_.end();
00329   for (; it != end; ++it)
00330   {
00331     (*it)->setMaterial(current_material_->getName());
00332   }
00333 
00334   regenerateAll();
00335 }
00336 
00337 void PointCloud::setDimensions(float width, float height, float depth)
00338 {
00339   width_ = width;
00340   height_ = height;
00341   depth_ = depth;
00342 
00343   Ogre::Vector4 size(width_, height_, depth_, 0.0f);
00344 
00345   V_PointCloudRenderable::iterator it = renderables_.begin();
00346   V_PointCloudRenderable::iterator end = renderables_.end();
00347   for (; it != end; ++it)
00348   {
00349     (*it)->setCustomParameter(SIZE_PARAMETER, size);
00350   }
00351 }
00352 
00353 void PointCloud::setAutoSize(bool auto_size)
00354 {
00355   V_PointCloudRenderable::iterator it = renderables_.begin();
00356   V_PointCloudRenderable::iterator end = renderables_.end();
00357   for (; it != end; ++it)
00358   {
00359     (*it)->setCustomParameter(AUTO_SIZE_PARAMETER, Ogre::Vector4(auto_size));
00360   }
00361 }
00362 
00363 void PointCloud::setCommonDirection(const Ogre::Vector3& vec)
00364 {
00365   common_direction_ = vec;
00366 
00367   V_PointCloudRenderable::iterator it = renderables_.begin();
00368   V_PointCloudRenderable::iterator end = renderables_.end();
00369   for (; it != end; ++it)
00370   {
00371     (*it)->setCustomParameter(NORMAL_PARAMETER, Ogre::Vector4(vec));
00372   }
00373 }
00374 
00375 void PointCloud::setCommonUpVector(const Ogre::Vector3& vec)
00376 {
00377   common_up_vector_ = vec;
00378 
00379   V_PointCloudRenderable::iterator it = renderables_.begin();
00380   V_PointCloudRenderable::iterator end = renderables_.end();
00381   for (; it != end; ++it)
00382   {
00383     (*it)->setCustomParameter(UP_PARAMETER, Ogre::Vector4(vec));
00384   }
00385 }
00386 
00387 void setAlphaBlending(const Ogre::MaterialPtr& mat)
00388 {
00389   if (mat->getBestTechnique())
00390   {
00391     mat->getBestTechnique()->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA );
00392     mat->getBestTechnique()->setDepthWriteEnabled( false );
00393   }
00394 }
00395 
00396 void setReplace(const Ogre::MaterialPtr& mat)
00397 {
00398   if (mat->getBestTechnique())
00399   {
00400     mat->getBestTechnique()->setSceneBlending( Ogre::SBT_REPLACE );
00401     mat->getBestTechnique()->setDepthWriteEnabled( true );
00402   }
00403 }
00404 
00405 void PointCloud::setAlpha(float alpha, bool per_point_alpha)
00406 {
00407   alpha_ = alpha;
00408 
00409   if ( alpha < 0.9998 || per_point_alpha )
00410   {
00411     setAlphaBlending(point_material_);
00412     setAlphaBlending(square_material_);
00413     setAlphaBlending(flat_square_material_);
00414     setAlphaBlending(sphere_material_);
00415     setAlphaBlending(tile_material_);
00416     setAlphaBlending(box_material_);
00417   }
00418   else
00419   {
00420     setReplace(point_material_);
00421     setReplace(square_material_);
00422     setReplace(flat_square_material_);
00423     setReplace(sphere_material_);
00424     setReplace(tile_material_);
00425     setReplace(box_material_);
00426   }
00427 
00428   Ogre::Vector4 alpha4(alpha_, alpha_, alpha_, alpha_);
00429   V_PointCloudRenderable::iterator it = renderables_.begin();
00430   V_PointCloudRenderable::iterator end = renderables_.end();
00431   for (; it != end; ++it)
00432   {
00433     (*it)->setCustomParameter(ALPHA_PARAMETER, alpha4);
00434   }
00435 }
00436 
00437 void PointCloud::addPoints(Point* points, uint32_t num_points)
00438 {
00439   if (num_points == 0)
00440   {
00441     return;
00442   }
00443   Ogre::Root* root = Ogre::Root::getSingletonPtr();
00444 
00445   if ( points_.size() < point_count_ + num_points )
00446   {
00447     points_.resize( point_count_ + num_points );
00448   }
00449 
00450   Point* begin = &points_.front() + point_count_;
00451   memcpy( begin, points, sizeof( Point ) * num_points );
00452 
00453   uint32_t vpp = getVerticesPerPoint();
00454   Ogre::RenderOperation::OperationType op_type;
00455   if (current_mode_supports_geometry_shader_)
00456   {
00457     op_type = Ogre::RenderOperation::OT_POINT_LIST;
00458   }
00459   else
00460   {
00461     if (render_mode_ == RM_POINTS)
00462     {
00463       op_type = Ogre::RenderOperation::OT_POINT_LIST;
00464     }
00465     else
00466     {
00467       op_type = Ogre::RenderOperation::OT_TRIANGLE_LIST;
00468     }
00469   }
00470 
00471   float* vertices = 0;
00472   if (current_mode_supports_geometry_shader_)
00473   {
00474     vertices = g_point_vertices;
00475   }
00476   else
00477   {
00478     if (render_mode_ == RM_POINTS)
00479     {
00480       vertices = g_point_vertices;
00481     }
00482     else if (render_mode_ == RM_SQUARES)
00483     {
00484       vertices = g_billboard_vertices;
00485     }
00486     else if (render_mode_ == RM_FLAT_SQUARES)
00487     {
00488       vertices = g_billboard_vertices;
00489     }
00490     else if (render_mode_ == RM_SPHERES)
00491     {
00492       vertices = g_billboard_sphere_vertices;
00493     }
00494     else if (render_mode_ == RM_TILES)
00495     {
00496       vertices = g_billboard_vertices;
00497     }
00498     else if (render_mode_ == RM_BOXES)
00499     {
00500       vertices = g_box_vertices;
00501     }
00502   }
00503 
00504   PointCloudRenderablePtr rend;
00505   Ogre::HardwareVertexBufferSharedPtr vbuf;
00506   void* vdata = 0;
00507   Ogre::RenderOperation* op = 0;
00508   float* fptr = 0;
00509 
00510   Ogre::AxisAlignedBox aabb;
00511   aabb.setNull();
00512   uint32_t current_vertex_count = 0;
00513   bounding_radius_ = 0.0f;
00514   uint32_t vertex_size = 0;
00515   uint32_t buffer_size = 0;
00516   for (uint32_t current_point = 0; current_point < num_points; ++current_point)
00517   {
00518     // if we didn't create a renderable yet,
00519     // or we've reached the vertex limit for the current renderable,
00520     // create a new one.
00521     while (!rend || current_vertex_count >= buffer_size)
00522     {
00523       if (rend)
00524       {
00525         ROS_ASSERT(current_vertex_count == buffer_size);
00526 
00527         op->vertexData->vertexCount = rend->getBuffer()->getNumVertices() - op->vertexData->vertexStart;
00528         ROS_ASSERT(op->vertexData->vertexCount + op->vertexData->vertexStart <= rend->getBuffer()->getNumVertices());
00529         vbuf->unlock();
00530         rend->setBoundingBox(aabb);
00531       }
00532 
00533       buffer_size = std::min<int>( VERTEX_BUFFER_CAPACITY, (num_points - current_point)*vpp );
00534 
00535       rend = createRenderable( buffer_size );
00536       vbuf = rend->getBuffer();
00537       vdata = vbuf->lock(Ogre::HardwareBuffer::HBL_NO_OVERWRITE);
00538 
00539       op = rend->getRenderOperation();
00540       op->operationType = op_type;
00541       current_vertex_count = 0;
00542 
00543       vertex_size = op->vertexData->vertexDeclaration->getVertexSize(0);
00544       fptr = (float*)((uint8_t*)vdata);
00545 
00546       aabb.setNull();
00547     }
00548 
00549     const Point& p = points[current_point];
00550 
00551     uint32_t color;
00552 
00553     if (color_by_index_)
00554     {
00555       // convert to ColourValue, so we can then convert to the rendersystem-specific color type
00556       color = (current_point + point_count_ + 1);
00557       Ogre::ColourValue c;
00558       c.a = 1.0f;
00559       c.r = ((color >> 16) & 0xff) / 255.0f;
00560       c.g = ((color >> 8) & 0xff) / 255.0f;
00561       c.b = (color & 0xff) / 255.0f;
00562       root->convertColourValue(c, &color);
00563     }
00564     else
00565     {
00566       Ogre::Root::getSingletonPtr()->convertColourValue( p.color, &color );
00567     }
00568 
00569     aabb.merge(p.position);
00570     bounding_box_.merge( p.position );
00571     bounding_radius_ = std::max( bounding_radius_, p.position.squaredLength() );
00572 
00573     float x = p.position.x;
00574     float y = p.position.y;
00575     float z = p.position.z;
00576 
00577     for (uint32_t j = 0; j < vpp; ++j, ++current_vertex_count)
00578     {
00579       *fptr++ = x;
00580       *fptr++ = y;
00581       *fptr++ = z;
00582 
00583       if (!current_mode_supports_geometry_shader_)
00584       {
00585         *fptr++ = vertices[(j*3)];
00586         *fptr++ = vertices[(j*3) + 1];
00587         *fptr++ = vertices[(j*3) + 2];
00588       }
00589 
00590       uint32_t* iptr = (uint32_t*)fptr;
00591       *iptr = color;
00592       ++fptr;
00593 
00594       ROS_ASSERT((uint8_t*)fptr <= (uint8_t*)vdata + rend->getBuffer()->getNumVertices() * vertex_size);
00595     }
00596   }
00597 
00598   op->vertexData->vertexCount = current_vertex_count - op->vertexData->vertexStart;
00599   rend->setBoundingBox(aabb);
00600   ROS_ASSERT(op->vertexData->vertexCount + op->vertexData->vertexStart <= rend->getBuffer()->getNumVertices());
00601 
00602   vbuf->unlock();
00603 
00604   point_count_ += num_points;
00605 
00606   shrinkRenderables();
00607 
00608   if (getParentSceneNode())
00609   {
00610     getParentSceneNode()->needUpdate();
00611   }
00612 }
00613 
00614 void PointCloud::popPoints(uint32_t num_points)
00615 {
00616   uint32_t vpp = getVerticesPerPoint();
00617 
00618   ROS_ASSERT(num_points <= point_count_);
00619   points_.erase(points_.begin(), points_.begin() + num_points);
00620 
00621   point_count_ -= num_points;
00622 
00623   // Now clear out popped points
00624   uint32_t popped_count = 0;
00625   while (popped_count < num_points * vpp)
00626   {
00627     PointCloudRenderablePtr rend = renderables_.front();
00628     Ogre::RenderOperation* op = rend->getRenderOperation();
00629 
00630     uint32_t popped = std::min((size_t)(num_points * vpp - popped_count), op->vertexData->vertexCount);
00631     op->vertexData->vertexStart += popped;
00632     op->vertexData->vertexCount -= popped;
00633 
00634     popped_count += popped;
00635 
00636     if (op->vertexData->vertexCount == 0)
00637     {
00638       renderables_.erase(renderables_.begin(), renderables_.begin() + 1);
00639 
00640       op->vertexData->vertexStart = 0;
00641       renderables_.push_back(rend);
00642     }
00643   }
00644   ROS_ASSERT(popped_count == num_points * vpp);
00645 
00646   // reset bounds
00647   bounding_box_.setNull();
00648   bounding_radius_ = 0.0f;
00649   for (uint32_t i = 0; i < point_count_; ++i)
00650   {
00651     Point& p = points_[i];
00652     bounding_box_.merge(p.position);
00653     bounding_radius_ = std::max(bounding_radius_, p.position.squaredLength());
00654   }
00655 
00656   shrinkRenderables();
00657 
00658   if (getParentSceneNode())
00659   {
00660     getParentSceneNode()->needUpdate();
00661   }
00662 }
00663 
00664 void PointCloud::shrinkRenderables()
00665 {
00666   while (!renderables_.empty())
00667   {
00668     PointCloudRenderablePtr rend = renderables_.back();
00669     Ogre::RenderOperation* op = rend->getRenderOperation();
00670     if (op->vertexData->vertexCount == 0)
00671     {
00672       renderables_.pop_back();
00673     }
00674     else
00675     {
00676       break;
00677     }
00678   }
00679 }
00680 
00681 void PointCloud::_notifyCurrentCamera(Ogre::Camera* camera)
00682 {
00683   MovableObject::_notifyCurrentCamera( camera );
00684 }
00685 
00686 void PointCloud::_updateRenderQueue(Ogre::RenderQueue* queue)
00687 {
00688   V_PointCloudRenderable::iterator it = renderables_.begin();
00689   V_PointCloudRenderable::iterator end = renderables_.end();
00690   for (; it != end; ++it)
00691   {
00692     queue->addRenderable((*it).get());
00693   }
00694 }
00695 
00696 void PointCloud::_notifyAttached(Ogre::Node *parent, bool isTagPoint)
00697 {
00698   MovableObject::_notifyAttached(parent, isTagPoint);
00699 }
00700 
00701 uint32_t PointCloud::getVerticesPerPoint()
00702 {
00703   if (current_mode_supports_geometry_shader_)
00704   {
00705     return 1;
00706   }
00707 
00708   if (render_mode_ == RM_POINTS)
00709   {
00710     return 1;
00711   }
00712 
00713   if (render_mode_ == RM_SQUARES)
00714   {
00715     return 6;
00716   }
00717 
00718   if (render_mode_ == RM_FLAT_SQUARES)
00719   {
00720     return 6;
00721   }
00722 
00723   if (render_mode_ == RM_TILES)
00724     {
00725       return 6;
00726     }
00727 
00728   if (render_mode_ == RM_SPHERES)
00729   {
00730     return 3;
00731   }
00732 
00733   if (render_mode_ == RM_BOXES)
00734   {
00735     return 36;
00736   }
00737 
00738   return 1;
00739 }
00740 
00741 void PointCloud::setPickColor(const Ogre::ColourValue& color)
00742 {
00743   pick_color_ = color;
00744   Ogre::Vector4 pick_col(pick_color_.r, pick_color_.g, pick_color_.b, pick_color_.a);
00745 
00746   V_PointCloudRenderable::iterator it = renderables_.begin();
00747   V_PointCloudRenderable::iterator end = renderables_.end();
00748   for (; it != end; ++it)
00749   {
00750     (*it)->setCustomParameter(PICK_COLOR_PARAMETER, pick_col);
00751   }
00752   getUserObjectBindings().setUserAny( "pick_handle", Ogre::Any( colorToHandle( color )));
00753 }
00754 
00755 PointCloudRenderablePtr PointCloud::createRenderable( int num_points )
00756 {
00757   PointCloudRenderablePtr rend(new PointCloudRenderable(this, num_points, !current_mode_supports_geometry_shader_));
00758   rend->setMaterial(current_material_->getName());
00759   Ogre::Vector4 size(width_, height_, depth_, 0.0f);
00760   Ogre::Vector4 alpha(alpha_, 0.0f, 0.0f, 0.0f);
00761   Ogre::Vector4 highlight(0.0f, 0.0f, 0.0f, 0.0f);
00762   Ogre::Vector4 pick_col(pick_color_.r, pick_color_.g, pick_color_.b, pick_color_.a);
00763   rend->setCustomParameter(SIZE_PARAMETER, size);
00764   rend->setCustomParameter(ALPHA_PARAMETER, alpha);
00765   rend->setCustomParameter(HIGHLIGHT_PARAMETER, highlight);
00766   rend->setCustomParameter(PICK_COLOR_PARAMETER, pick_col);
00767   rend->setCustomParameter(NORMAL_PARAMETER, Ogre::Vector4(common_direction_));
00768   rend->setCustomParameter(UP_PARAMETER, Ogre::Vector4(common_up_vector_));
00769   if (getParentSceneNode())
00770   {
00771     getParentSceneNode()->attachObject(rend.get());
00772   }
00773   renderables_.push_back(rend);
00774 
00775   return rend;
00776 }
00777 
00778 #if (OGRE_VERSION_MAJOR >= 1 && OGRE_VERSION_MINOR >= 6)
00779 void PointCloud::visitRenderables(Ogre::Renderable::Visitor* visitor, bool debugRenderables)
00780 {
00781 
00782 }
00783 #endif
00784 
00785 
00789 
00790 PointCloudRenderable::PointCloudRenderable(PointCloud* parent, int num_points, bool use_tex_coords)
00791 : parent_(parent)
00792 {
00793   // Initialize render operation
00794   mRenderOp.operationType = Ogre::RenderOperation::OT_POINT_LIST;
00795   mRenderOp.useIndexes = false;
00796   mRenderOp.vertexData = new Ogre::VertexData;
00797   mRenderOp.vertexData->vertexStart = 0;
00798   mRenderOp.vertexData->vertexCount = 0;
00799 
00800   Ogre::VertexDeclaration *decl = mRenderOp.vertexData->vertexDeclaration;
00801   size_t offset = 0;
00802 
00803   decl->addElement(0, offset, Ogre::VET_FLOAT3, Ogre::VES_POSITION);
00804   offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT3);
00805 
00806   if (use_tex_coords)
00807   {
00808     decl->addElement(0, offset, Ogre::VET_FLOAT3, Ogre::VES_TEXTURE_COORDINATES, 0);
00809     offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT3);
00810   }
00811 
00812   decl->addElement(0, offset, Ogre::VET_COLOUR, Ogre::VES_DIFFUSE);
00813 
00814   Ogre::HardwareVertexBufferSharedPtr vbuf =
00815     Ogre::HardwareBufferManager::getSingleton().createVertexBuffer(
00816       mRenderOp.vertexData->vertexDeclaration->getVertexSize(0),
00817       num_points,
00818       Ogre::HardwareBuffer::HBU_DYNAMIC);
00819 
00820   // Bind buffer
00821   mRenderOp.vertexData->vertexBufferBinding->setBinding(0, vbuf);
00822 }
00823 
00824 PointCloudRenderable::~PointCloudRenderable()
00825 {
00826   delete mRenderOp.vertexData;
00827   delete mRenderOp.indexData;
00828 }
00829 
00830 Ogre::HardwareVertexBufferSharedPtr PointCloudRenderable::getBuffer()
00831 {
00832   return mRenderOp.vertexData->vertexBufferBinding->getBuffer(0);
00833 }
00834 
00835 void PointCloudRenderable::_notifyCurrentCamera(Ogre::Camera* camera)
00836 {
00837   SimpleRenderable::_notifyCurrentCamera( camera );
00838 }
00839 
00840 Ogre::Real PointCloudRenderable::getBoundingRadius(void) const
00841 {
00842   return Ogre::Math::Sqrt(std::max(mBox.getMaximum().squaredLength(), mBox.getMinimum().squaredLength()));
00843 }
00844 
00845 Ogre::Real PointCloudRenderable::getSquaredViewDepth(const Ogre::Camera* cam) const
00846 {
00847   Ogre::Vector3 vMin, vMax, vMid, vDist;
00848    vMin = mBox.getMinimum();
00849    vMax = mBox.getMaximum();
00850    vMid = ((vMax - vMin) * 0.5) + vMin;
00851    vDist = cam->getDerivedPosition() - vMid;
00852 
00853    return vDist.squaredLength();
00854 }
00855 
00856 void PointCloudRenderable::getWorldTransforms(Ogre::Matrix4* xform) const
00857 {
00858    parent_->getWorldTransforms(xform);
00859 }
00860 
00861 const Ogre::LightList& PointCloudRenderable::getLights() const
00862 {
00863   return parent_->queryLights();
00864 }
00865 
00866 } // namespace rviz


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Mon Oct 6 2014 07:26:35