mesh_resource_marker.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 "mesh_resource_marker.h"
00031 
00032 #include "marker_selection_handler.h"
00033 #include "rviz/default_plugin/marker_display.h"
00034 #include "rviz/selection/selection_manager.h"
00035 
00036 #include "rviz/visualization_manager.h"
00037 #include "rviz/mesh_loader.h"
00038 #include "marker_display.h"
00039 
00040 #include <OGRE/OgreSceneNode.h>
00041 #include <OGRE/OgreSceneManager.h>
00042 #include <OGRE/OgreEntity.h>
00043 #include <OGRE/OgreSubEntity.h>
00044 #include <OGRE/OgreMaterialManager.h>
00045 #include <OGRE/OgreTextureManager.h>
00046 
00047 namespace rviz
00048 {
00049 
00050 MeshResourceMarker::MeshResourceMarker(MarkerDisplay* owner, VisualizationManager* manager, Ogre::SceneNode* parent_node)
00051 : MarkerBase(owner, manager, parent_node)
00052 , entity_(0)
00053 {
00054 }
00055 
00056 MeshResourceMarker::~MeshResourceMarker()
00057 {
00058   reset();
00059 }
00060 
00061 void MeshResourceMarker::reset()
00062 {
00063   //destroy entity
00064   if (entity_)
00065   {
00066     vis_manager_->getSceneManager()->destroyEntity( entity_ );
00067     entity_ = 0;
00068   }
00069 
00070   // destroy all the materials we've created
00071   S_MaterialPtr::iterator it;
00072   for ( it = materials_.begin(); it!=materials_.end(); it++ )
00073   {
00074     Ogre::MaterialPtr material = *it;
00075     if (!material.isNull())
00076     {
00077       for (size_t i = 0; i < material->getNumTechniques(); ++i)
00078       {
00079         Ogre::Technique* t = material->getTechnique(i);
00080         // hack hack hack, really need to do a shader-based way of picking, rather than
00081         // creating a texture for each object
00082         if (t->getSchemeName() == "Pick")
00083         {
00084           Ogre::TextureManager::getSingleton().remove(t->getPass(0)->getTextureUnitState(0)->getTextureName());
00085         }
00086       }
00087 
00088       material->unload();
00089       Ogre::MaterialManager::getSingleton().remove(material->getName());
00090     }
00091   }
00092   materials_.clear();
00093 }
00094 
00095 void MeshResourceMarker::onNewMessage(const MarkerConstPtr& old_message, const MarkerConstPtr& new_message)
00096 {
00097   ROS_ASSERT(new_message->type == visualization_msgs::Marker::MESH_RESOURCE);
00098 
00099   bool need_color = false;
00100 
00101   scene_node_->setVisible(false);
00102 
00103   if( !entity_ ||
00104       old_message->mesh_resource != new_message->mesh_resource ||
00105       old_message->mesh_use_embedded_materials != new_message->mesh_use_embedded_materials )
00106   {
00107     reset();
00108 
00109     if (new_message->mesh_resource.empty())
00110     {
00111       return;
00112     }
00113 
00114     if (loadMeshFromResource(new_message->mesh_resource).isNull())
00115     {
00116       std::stringstream ss;
00117       ss << "Mesh resource marker [" << getStringID() << "] could not load [" << new_message->mesh_resource << "]";
00118       if ( owner_ )
00119       {
00120         owner_->setMarkerStatus(getID(), status_levels::Error, ss.str());
00121       }
00122       ROS_DEBUG("%s", ss.str().c_str());
00123       return;
00124     }
00125 
00126     static uint32_t count = 0;
00127     std::stringstream ss;
00128     ss << "mesh_resource_marker_" << count++;
00129     std::string id = ss.str();
00130     entity_ = vis_manager_->getSceneManager()->createEntity(id, new_message->mesh_resource);
00131     scene_node_->attachObject(entity_);
00132     need_color = true;
00133 
00134     // create a default material for any sub-entities which don't have their own.
00135     ss << "Material";
00136     Ogre::MaterialPtr default_material = Ogre::MaterialManager::getSingleton().create( ss.str(), ROS_PACKAGE_NAME );
00137     default_material->setReceiveShadows(false);
00138     default_material->getTechnique(0)->setLightingEnabled(true);
00139     default_material->getTechnique(0)->setAmbient( 0.5, 0.5, 0.5 );
00140     materials_.insert( default_material );
00141 
00142     if ( new_message->mesh_use_embedded_materials )
00143     {
00144       // make clones of all embedded materials so selection works correctly
00145       S_MaterialPtr materials = getMaterials();
00146 
00147       S_MaterialPtr::iterator it;
00148       for ( it = materials.begin(); it!=materials.end(); it++ )
00149       {
00150         if( (*it)->getName() != "BaseWhiteNoLighting" )
00151         {
00152           Ogre::MaterialPtr new_material = (*it)->clone( id + (*it)->getName() );
00153           materials_.insert( new_material );
00154         }
00155       }
00156 
00157       // make sub-entities use cloned materials
00158       for (uint32_t i = 0; i < entity_->getNumSubEntities(); ++i)
00159       {
00160         std::string mat_name = entity_->getSubEntity(i)->getMaterialName();
00161         if( mat_name != "BaseWhiteNoLighting" )
00162         {
00163           entity_->getSubEntity(i)->setMaterialName( id + mat_name );
00164         }
00165         else
00166         {
00167           // BaseWhiteNoLighting is the default material Ogre uses
00168           // when it sees a mesh with no material.  Here we replace
00169           // that with our default_material which gets colored with
00170           // new_message->color.
00171           entity_->getSubEntity(i)->setMaterial( default_material );
00172         }
00173       }
00174     }
00175     else
00176     {
00177       entity_->setMaterial( default_material );
00178     }
00179 
00180     vis_manager_->getSelectionManager()->removeObject(coll_);
00181     coll_ = vis_manager_->getSelectionManager()->createCollisionForEntity(entity_, SelectionHandlerPtr(new MarkerSelectionHandler(this, MarkerID(new_message->ns, new_message->id))), coll_);
00182   }
00183 
00184   if( need_color ||
00185       old_message->color.r != new_message->color.r ||
00186       old_message->color.g != new_message->color.g ||
00187       old_message->color.b != new_message->color.b ||
00188       old_message->color.a != new_message->color.a )
00189   {
00190     float r = new_message->color.r;
00191     float g = new_message->color.g;
00192     float b = new_message->color.b;
00193     float a = new_message->color.a;
00194 
00195     // Old way was to ignore the color and alpha when using embedded
00196     // materials, which meant you could leave them unset, which means
00197     // 0.  Since we now USE the color and alpha values, leaving them
00198     // all 0 will mean the object will be invisible.  Therefore detect
00199     // the situation where RGBA are all 0 and treat that the same as
00200     // all 1 (full white).
00201     if( new_message->mesh_use_embedded_materials && r == 0 && g == 0 && b == 0 && a == 0 )
00202     {
00203       r = 1; g = 1; b = 1; a = 1;
00204     }
00205 
00206     Ogre::SceneBlendType blending;
00207     bool depth_write;
00208 
00209     if ( a < 0.9998 )
00210     {
00211       blending = Ogre::SBT_TRANSPARENT_ALPHA;
00212       depth_write = false;
00213     }
00214     else
00215     {
00216       blending = Ogre::SBT_REPLACE;
00217       depth_write = true;
00218     }
00219 
00220     S_MaterialPtr::iterator it;
00221     for( it = materials_.begin(); it != materials_.end(); it++ )
00222     {    
00223       Ogre::Technique* technique = (*it)->getTechnique( 0 );
00224 
00225       technique->setAmbient( r*0.5, g*0.5, b*0.5 );
00226       technique->setDiffuse( r, g, b, a );
00227       technique->setSceneBlending( blending );
00228       technique->setDepthWriteEnabled( depth_write );
00229     }
00230   }
00231 
00232   Ogre::Vector3 pos, scale;
00233   Ogre::Quaternion orient;
00234   transform(new_message, pos, orient, scale);
00235 
00236   scene_node_->setVisible(true);
00237   setPosition(pos);
00238   setOrientation(orient);
00239 
00240   // In Ogre, mesh surface normals are not normalized if object is not
00241   // scaled.  This forces the surface normals to be renormalized by
00242   // invisibly tweaking the scale.
00243   if( scale.x == 1.0 && scale.y == 1.0 && scale.z == 1.0 )
00244   {
00245     scale.z = 1.0001;
00246   }
00247   scene_node_->setScale(scale);
00248 }
00249 
00250 S_MaterialPtr MeshResourceMarker::getMaterials()
00251 {
00252   S_MaterialPtr materials;
00253   if( entity_ )
00254   {
00255     extractMaterials( entity_, materials );
00256   }
00257   return materials;
00258 }
00259 
00260 }
00261 


rviz
Author(s): Dave Hershberger, Josh Faust
autogenerated on Mon Jan 6 2014 11:54:32