lines_renderer.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2010, 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 <rve_render_server/batching/lines_renderer.h>
00031 #include <rve_render_server/init.h>
00032 #include <rve_render_server/renderer.h>
00033 #include <rve_render_server/batching/lines_material_generator.h>
00034 #include <rve_render_server/convert.h>
00035 
00036 #include <rve_msgs/Lines.h>
00037 
00038 #include <OGRE/OgreRoot.h>
00039 #include <OGRE/OgreSceneNode.h>
00040 #include <OGRE/OgreHardwareBufferManager.h>
00041 #include <OGRE/OgreHardwareVertexBuffer.h>
00042 
00043 #define LINES_PER_VBO (1024 * 8)
00044 
00045 namespace rve_render_server
00046 {
00047 
00048 static float g_billboard_offsets[6] =
00049 {
00050   -0.5f,
00051   0.5f,
00052   -0.5f,
00053   0.5f,
00054   -0.5f,
00055   0.5f,
00056 };
00057 
00058 LinesRenderable::LinesRenderable(const LinesRendererDesc& desc, bool alpha)
00059 : Parent(desc, alpha)
00060 {
00061   Ogre::Vector4 size(desc_.scale.x, desc_.scale.y, desc_.scale.z, 0.0f);
00062   setCustomParameter(LinesRendererDesc::CustomParam_Size, size);
00063 
00064   mRenderOp.operationType = isBillboard() ? Ogre::RenderOperation::OT_TRIANGLE_LIST : Ogre::RenderOperation::OT_LINE_LIST;
00065   mRenderOp.useIndexes = false;
00066   mRenderOp.vertexData = new Ogre::VertexData;
00067   mRenderOp.vertexData->vertexStart = 0;
00068   mRenderOp.vertexData->vertexCount = 0;
00069 
00070   Ogre::VertexDeclaration *decl = mRenderOp.vertexData->vertexDeclaration;
00071   size_t offset = 0;
00072 
00073   decl->addElement(0, offset, Ogre::VET_FLOAT3, Ogre::VES_POSITION);
00074   offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT3);
00075 
00076   uint32_t tex_coord_num = 0;
00077   if (isBillboard())
00078   {
00079     decl->addElement(0, offset, Ogre::VET_FLOAT4, Ogre::VES_TEXTURE_COORDINATES, tex_coord_num++);
00080     offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT4);
00081   }
00082 
00083   decl->addElement(0, offset, Ogre::VET_COLOUR, Ogre::VES_DIFFUSE);
00084 
00085   Ogre::HardwareVertexBufferSharedPtr vbuf =
00086     Ogre::HardwareBufferManager::getSingleton().createVertexBuffer(
00087       mRenderOp.vertexData->vertexDeclaration->getVertexSize(0),
00088           LINES_PER_VBO * getVerticesPerLine(),
00089       Ogre::HardwareBuffer::HBU_DYNAMIC_WRITE_ONLY);
00090 
00091   // Bind buffer
00092   mRenderOp.vertexData->vertexBufferBinding->setBinding(0, vbuf);
00093 }
00094 
00095 LinesRenderable::~LinesRenderable()
00096 {
00097   delete mRenderOp.vertexData;
00098   delete mRenderOp.indexData;
00099 }
00100 
00101 void LinesRenderable::add(const rve_common::UUID& id, const rve_msgs::Lines& lines, uint32_t start, uint32_t& out_start, uint32_t& out_count)
00102 {
00103   ROS_ASSERT(lines.positions.size() == lines.colors.size());
00104   ROS_ASSERT(!isList() || lines.positions.size() % 2 == 0);
00105 
00106   uint32_t verts_per_vertex = getVerticesPerVertex();
00107   uint32_t verts_per_line = getVerticesPerLine();
00108   uint32_t line_stride = getVertexStride() * verts_per_line;
00109   bool alpha = alpha_;
00110 
00111   Ogre::HardwareVertexBufferSharedPtr vbuf = mRenderOp.vertexData->vertexBufferBinding->getBuffer(0);
00112   out_start = (mRenderOp.vertexData->vertexStart / verts_per_line) + (mRenderOp.vertexData->vertexCount / verts_per_line);
00113 
00114   uint32_t end = std::min((size_t)LINES_PER_VBO, out_start + (lines.positions.size() - start));
00115   out_count = 0;
00116 
00117   uint32_t lock_start = out_start * line_stride * verts_per_line;
00118   uint32_t lock_size = end * line_stride * verts_per_line;
00119   void* data = vbuf->lock(lock_start, lock_size, Ogre::HardwareVertexBuffer::HBL_NO_OVERWRITE);
00120   float* fptr = (float*)data;
00121 
00122   if (isBillboard())
00123   {
00124     outputBillboards(lines, fptr, start, out_start, end, alpha, out_count);
00125   }
00126   else
00127   {
00128     outputLines(lines, fptr, start, out_start, end, alpha, out_count);
00129   }
00130 
00131   vbuf->unlock();
00132 
00133   mRenderOp.vertexData->vertexCount += out_count * verts_per_vertex;
00134   count_ += out_count;
00135 }
00136 
00137 void LinesRenderable::outputLines(const rve_msgs::Lines& lines, float* fptr, uint32_t line_start, uint32_t vert_start, uint32_t end, bool alpha, uint32_t& out_count)
00138 {
00139   Ogre::Root* root = Ogre::Root::getSingletonPtr();
00140 
00141   rve_msgs::Lines::_positions_type::const_iterator pos_it = lines.positions.begin() + line_start;
00142   rve_msgs::Lines::_colors_type::const_iterator col_it = lines.colors.begin() + line_start;
00143   for (uint32_t i = vert_start; i < end; ++i, ++pos_it, ++col_it)
00144   {
00145     float a = col_it->a;
00146     if ((a < 0.99) != alpha)
00147     {
00148       continue;
00149     }
00150 
00151     Ogre::Vector3 pos = fromRobot(Ogre::Vector3(pos_it->x, pos_it->y, pos_it->z));
00152     mBox.merge(pos);
00153 
00154     float r = col_it->r;
00155     float g = col_it->g;
00156     float b = col_it->b;
00157 
00158     uint32_t color = 0;
00159     root->convertColourValue(Ogre::ColourValue(r, g, b, a), &color);
00160 
00161     ++out_count;
00162 
00163     *fptr++ = pos.x;
00164     *fptr++ = pos.y;
00165     *fptr++ = pos.z;
00166 
00167     uint32_t* iptr = (uint32_t*)fptr;
00168     *iptr = color;
00169     ++fptr;
00170   }
00171 }
00172 
00173 void LinesRenderable::outputBillboards(const rve_msgs::Lines& lines, float* fptr, uint32_t line_start, uint32_t vert_start, uint32_t end, bool alpha, uint32_t& out_count)
00174 {
00175   Ogre::Root* root = Ogre::Root::getSingletonPtr();
00176 
00177   float* offsets = getOffsets();
00178 
00179   rve_msgs::Lines::_positions_type::const_iterator pos_it = lines.positions.begin() + line_start;
00180   rve_msgs::Lines::_colors_type::const_iterator col_it = lines.colors.begin() + line_start;
00181   for (uint32_t i = vert_start; i < end; i += 2, ++pos_it, ++col_it)
00182   {
00183     Ogre::Vector3 pos0 = fromRobot(Ogre::Vector3(pos_it->x, pos_it->y, pos_it->z));
00184     ++pos_it;
00185     Ogre::Vector3 pos1 = fromRobot(Ogre::Vector3(pos_it->x, pos_it->y, pos_it->z));
00186     mBox.merge(pos0);
00187     mBox.merge(pos1);
00188 
00189     Ogre::Vector3 line_dir = pos1 - pos0;
00190     line_dir.normalise();
00191 
00192     uint32_t color0 = 0;
00193     uint32_t color1 = 0;
00194     root->convertColourValue(Ogre::ColourValue(col_it->r, col_it->g, col_it->b, col_it->a), &color0);
00195     bool has_alpha = col_it->a < 0.99;
00196     ++col_it;
00197     root->convertColourValue(Ogre::ColourValue(col_it->r, col_it->g, col_it->b, col_it->a), &color1);
00198     has_alpha = col_it->a < 0.99;
00199     if (has_alpha != alpha)
00200     {
00201       continue;
00202     }
00203 
00204     Ogre::Vector3 positions[6] =
00205     {
00206       pos0,
00207       pos0,
00208       pos1,
00209       pos1,
00210       pos1,
00211       pos0
00212     };
00213 
00214     uint32_t colors[6] =
00215     {
00216      color0,
00217      color0,
00218      color1,
00219      color1,
00220      color1,
00221      color0
00222     };
00223 
00224     out_count += 2;
00225 
00226     for (uint32_t j = 0; j < 6; ++j)
00227     {
00228       *fptr++ = positions[j].x;
00229       *fptr++ = positions[j].y;
00230       *fptr++ = positions[j].z;
00231 
00232       *fptr++ = line_dir.x;
00233       *fptr++ = line_dir.y;
00234       *fptr++ = line_dir.z;
00235       *fptr++ = offsets[j];
00236 
00237       uint32_t* iptr = (uint32_t*)fptr;
00238       *iptr = colors[j];
00239       ++fptr;
00240     }
00241   }
00242 }
00243 
00244 void LinesRenderable::remove(uint32_t start, uint32_t count)
00245 {
00246   ROS_ASSERT_MSG(count <= count_, "count = %d, count_ = %d", count, count_);
00247   ROS_ASSERT_MSG(start + count < LINES_PER_VBO, "start = %d, count = %d, LINES_PER_VBO = %d", start, count, LINES_PER_VBO);
00248 
00249   uint32_t verts_per_line = getVerticesPerLine();
00250   uint32_t line_stride = getVertexStride() * verts_per_line;
00251 
00252   Ogre::HardwareVertexBufferSharedPtr vbuf = mRenderOp.vertexData->vertexBufferBinding->getBuffer(0);
00253   uint8_t* data = (uint8_t*)vbuf->lock(start * line_stride * verts_per_line, count * line_stride * verts_per_line, Ogre::HardwareVertexBuffer::HBL_NORMAL);
00254 
00255   uint32_t total_vertices = verts_per_line * count;
00256   data = data + (line_stride * verts_per_line * start);
00257   for (uint32_t i = 0; i < total_vertices; ++i)
00258   {
00259     // Assign positions outside the viewable area
00260     float* fptr = (float*)data;
00261     *fptr++ = 99999999.0f;
00262     *fptr++ = 99999999.0f;
00263     *fptr++ = 99999999.0f;
00264 
00265     data += line_stride;
00266   }
00267 
00268   count_ -= count;
00269 
00270   vbuf->unlock();
00271 
00272   if (isEmpty())
00273   {
00274     mBox.setNull();
00275   }
00276 }
00277 
00278 uint32_t LinesRenderable::getElementsPerVBO()
00279 {
00280   return LINES_PER_VBO;
00281 }
00282 
00283 uint32_t LinesRenderable::getVertexStride()
00284 {
00285   return mRenderOp.vertexData->vertexDeclaration->getVertexSize(0);
00286 }
00287 
00288 float* LinesRenderable::getOffsets()
00289 {
00290   if (isBillboard())
00291   {
00292     return g_billboard_offsets;
00293   }
00294 
00295   return 0;
00296 }
00297 
00298 uint32_t LinesRenderable::getVerticesPerVertex()
00299 {
00300   if (isBillboard())
00301   {
00302     return 3;
00303   }
00304 
00305   return 1;
00306 }
00307 
00308 uint32_t LinesRenderable::getVerticesPerLine()
00309 {
00310   return 2 * getVerticesPerVertex();
00311 }
00312 
00313 bool LinesRenderable::isList()
00314 {
00315   return true;
00316 }
00317 
00318 bool LinesRenderable::isBillboard()
00319 {
00320   return desc_.type == rve_msgs::Lines::TYPE_BILLBOARD_LIST;
00321 }
00322 
00326 
00327 LinesRenderer::LinesRenderer(Ogre::SceneManager* scene_manager, const LinesRendererDesc& desc)
00328 : Parent(scene_manager, desc)
00329 {
00330 }
00331 
00332 std::pair<Ogre::MaterialPtr, Ogre::MaterialPtr> LinesRenderer::createMaterials(const LinesRendererDesc& desc)
00333 {
00334   return generateMaterialsForLines(desc);
00335 }
00336 
00337 size_t LinesRenderer::getInputCount(const rve_msgs::Lines& lines)
00338 {
00339   return lines.positions.size();
00340 }
00341 
00342 } // namespace rve_render_server


rve_render_server
Author(s): Josh Faust
autogenerated on Wed Dec 11 2013 14:31:15