billboard_line.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 "billboard_line.h"
00031 
00032 #include <OgreSceneManager.h>
00033 #include <OgreSceneNode.h>
00034 #include <OgreVector3.h>
00035 #include <OgreQuaternion.h>
00036 #include <OgreBillboardChain.h>
00037 #include <OgreMaterialManager.h>
00038 #include <OgreTechnique.h>
00039 
00040 #include <sstream>
00041 
00042 #include <ros/assert.h>
00043 
00044 #define MAX_ELEMENTS (65536/4)
00045 
00046 namespace rviz
00047 {
00048 
00049 BillboardLine::BillboardLine( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node )
00050 : Object( scene_manager )
00051 , width_( 0.1f )
00052 , current_line_(0)
00053 , total_elements_(0)
00054 , num_lines_(1)
00055 , max_points_per_line_(100)
00056 , lines_per_chain_(0)
00057 , current_chain_(0)
00058 , elements_in_current_chain_(0)
00059 {
00060   if ( !parent_node )
00061   {
00062     parent_node = scene_manager_->getRootSceneNode();
00063   }
00064 
00065   scene_node_ = parent_node->createChildSceneNode();
00066 
00067   static int count = 0;
00068   std::stringstream ss;
00069   ss << "BillboardLineMaterial" << count++;
00070   material_ = Ogre::MaterialManager::getSingleton().create( ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME );
00071   material_->setReceiveShadows(false);
00072   material_->getTechnique(0)->setLightingEnabled(false);
00073 
00074   setNumLines(num_lines_);
00075   setMaxPointsPerLine(max_points_per_line_);
00076 }
00077 
00078 BillboardLine::~BillboardLine()
00079 {
00080   V_Chain::iterator it = chains_.begin();
00081   V_Chain::iterator end = chains_.end();
00082   for (;it != end; ++it)
00083   {
00084     scene_manager_->destroyBillboardChain(*it);
00085   }
00086 
00087   scene_manager_->destroySceneNode( scene_node_->getName() );
00088 
00089   Ogre::MaterialManager::getSingleton().remove(material_->getName());
00090 }
00091 
00092 Ogre::BillboardChain* BillboardLine::createChain()
00093 {
00094   std::stringstream ss;
00095   static int count = 0;
00096   ss << "BillboardLine chain" << count++;
00097   Ogre::BillboardChain* chain = scene_manager_->createBillboardChain(ss.str());
00098   chain->setMaterialName( material_->getName() );
00099   scene_node_->attachObject( chain );
00100 
00101   chains_.push_back(chain);
00102 
00103   return chain;
00104 }
00105 
00106 void BillboardLine::clear()
00107 {
00108   V_Chain::iterator it = chains_.begin();
00109   V_Chain::iterator end = chains_.end();
00110   for (; it != end; ++it)
00111   {
00112     (*it)->clearAllChains();
00113   }
00114 
00115   current_line_ = 0;
00116   total_elements_ = 0;
00117   current_chain_ = 0;
00118   elements_in_current_chain_ = 0;
00119 
00120   for (V_uint32::iterator it = num_elements_.begin(); it != num_elements_.end(); ++it)
00121   {
00122     *it = 0;
00123   }
00124 }
00125 
00126 void BillboardLine::setupChains()
00127 {
00128   uint32_t total_points = max_points_per_line_ * num_lines_;
00129   uint32_t num_chains = total_points / MAX_ELEMENTS;
00130   if (total_points % MAX_ELEMENTS != 0)
00131   {
00132     ++num_chains;
00133   }
00134 
00135   for (uint32_t i = chains_.size(); i < num_chains; ++i)
00136   {
00137     createChain();
00138   }
00139 
00140   lines_per_chain_ = max_points_per_line_ > 0 ? MAX_ELEMENTS / max_points_per_line_ : 1;
00141 
00142   V_Chain::iterator it = chains_.begin();
00143   V_Chain::iterator end = chains_.end();
00144   for (;it != end; ++it)
00145   {
00146     (*it)->setMaxChainElements(max_points_per_line_);
00147 
00148     // shorten the number of chains in the last bbchain, to avoid memory wasteage
00149     if (it + 1 == end)
00150     {
00151       uint32_t lines_left = num_lines_ % lines_per_chain_;
00152 
00153       // Handle the case where num_lines_ is a multiple of lines_per_chain
00154       if (lines_left == 0) {
00155           (*it)->setNumberOfChains(lines_per_chain_);
00156       }
00157       else
00158       {
00159           (*it)->setNumberOfChains(lines_left);
00160       }
00161     }
00162     else
00163     {
00164       (*it)->setNumberOfChains(lines_per_chain_);
00165     }
00166   }
00167 }
00168 
00169 void BillboardLine::setMaxPointsPerLine(uint32_t max)
00170 {
00171   max_points_per_line_ = max;
00172 
00173   setupChains();
00174 }
00175 
00176 void BillboardLine::setNumLines(uint32_t num)
00177 {
00178   num_lines_ = num;
00179 
00180   setupChains();
00181 
00182   num_elements_.resize(num);
00183 
00184   for (V_uint32::iterator it = num_elements_.begin(); it != num_elements_.end(); ++it)
00185   {
00186     *it = 0;
00187   }
00188 }
00189 
00190 void BillboardLine::newLine()
00191 {
00192   ++current_line_;
00193 
00194   ROS_ASSERT(current_line_ < num_lines_);
00195 }
00196 
00197 void BillboardLine::addPoint( const Ogre::Vector3& point )
00198 {
00199   addPoint(point, color_);
00200 }
00201 
00202 void BillboardLine::addPoint( const Ogre::Vector3& point, const Ogre::ColourValue& color )
00203 {
00204   ++num_elements_[current_line_];
00205   ++total_elements_;
00206 
00207   ROS_ASSERT(num_elements_[current_line_] <= max_points_per_line_);
00208 
00209   ++elements_in_current_chain_;
00210   if (elements_in_current_chain_ > MAX_ELEMENTS)
00211   {
00212     ++current_chain_;
00213     elements_in_current_chain_ = 1;
00214   }
00215 
00216   Ogre::BillboardChain::Element e;
00217   e.position = point;
00218   e.width = width_;
00219   e.colour = color;
00220   chains_[current_chain_]->addChainElement(current_line_ % lines_per_chain_ , e);
00221 }
00222 
00223 void BillboardLine::setLineWidth( float width )
00224 {
00225   width_ = width;
00226 
00227   for (uint32_t line = 0; line < num_lines_; ++line)
00228   {
00229     uint32_t element_count = num_elements_[line];
00230 
00231     for ( uint32_t i = 0; i < element_count; ++i )
00232     {
00233       Ogre::BillboardChain* c = chains_[line / lines_per_chain_];
00234       Ogre::BillboardChain::Element e = c->getChainElement(line % lines_per_chain_, i);
00235 
00236       e.width = width_;
00237       c->updateChainElement(line % lines_per_chain_, i, e);
00238     }
00239   }
00240 }
00241 
00242 void BillboardLine::setPosition( const Ogre::Vector3& position )
00243 {
00244   scene_node_->setPosition( position );
00245 }
00246 
00247 void BillboardLine::setOrientation( const Ogre::Quaternion& orientation )
00248 {
00249   scene_node_->setOrientation( orientation );
00250 }
00251 
00252 void BillboardLine::setScale( const Ogre::Vector3& scale )
00253 {
00254   // Setting scale doesn't really make sense here
00255 }
00256 
00257 void BillboardLine::setColor( float r, float g, float b, float a )
00258 {
00259   if ( a < 0.9998 )
00260   {
00261     material_->getTechnique(0)->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA );
00262     material_->getTechnique(0)->setDepthWriteEnabled( false );
00263   }
00264   else
00265   {
00266     material_->getTechnique(0)->setSceneBlending( Ogre::SBT_REPLACE );
00267     material_->getTechnique(0)->setDepthWriteEnabled( true );
00268   }
00269 
00270   color_ = Ogre::ColourValue( r, g, b, a );
00271 
00272   for (uint32_t line = 0; line < num_lines_; ++line)
00273   {
00274     uint32_t element_count = num_elements_[line];
00275 
00276     for ( uint32_t i = 0; i < element_count; ++i )
00277     {
00278       Ogre::BillboardChain* c = chains_[line / lines_per_chain_];
00279       Ogre::BillboardChain::Element e = c->getChainElement(line % lines_per_chain_, i);
00280 
00281       e.colour = color_;
00282       c->updateChainElement(line % lines_per_chain_, i, e);
00283     }
00284   }
00285 }
00286 
00287 const Ogre::Vector3& BillboardLine::getPosition()
00288 {
00289   return scene_node_->getPosition();
00290 }
00291 
00292 const Ogre::Quaternion& BillboardLine::getOrientation()
00293 {
00294   return scene_node_->getOrientation();
00295 }
00296 
00297 } // namespace rviz


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Thu Jun 6 2019 18:02:15