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/display_context.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, DisplayContext* context, Ogre::SceneNode* parent_node)
00051 : MarkerBase(owner, context, 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     context_->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       material->unload();
00078       Ogre::MaterialManager::getSingleton().remove(material->getName());
00079     }
00080   }
00081   materials_.clear();
00082 }
00083 
00084 void MeshResourceMarker::onNewMessage(const MarkerConstPtr& old_message, const MarkerConstPtr& new_message)
00085 {
00086   ROS_ASSERT(new_message->type == visualization_msgs::Marker::MESH_RESOURCE);
00087 
00088   bool need_color = false;
00089 
00090   scene_node_->setVisible(false);
00091 
00092   if( !entity_ ||
00093       old_message->mesh_resource != new_message->mesh_resource ||
00094       old_message->mesh_use_embedded_materials != new_message->mesh_use_embedded_materials )
00095   {
00096     reset();
00097 
00098     if (new_message->mesh_resource.empty())
00099     {
00100       return;
00101     }
00102 
00103     if (loadMeshFromResource(new_message->mesh_resource).isNull())
00104     {
00105       std::stringstream ss;
00106       ss << "Mesh resource marker [" << getStringID() << "] could not load [" << new_message->mesh_resource << "]";
00107       if ( owner_ )
00108       {
00109         owner_->setMarkerStatus(getID(), StatusProperty::Error, ss.str());
00110       }
00111       ROS_DEBUG("%s", ss.str().c_str());
00112       return;
00113     }
00114 
00115     static uint32_t count = 0;
00116     std::stringstream ss;
00117     ss << "mesh_resource_marker_" << count++;
00118     std::string id = ss.str();
00119     entity_ = context_->getSceneManager()->createEntity(id, new_message->mesh_resource);
00120     scene_node_->attachObject(entity_);
00121     need_color = true;
00122 
00123     // create a default material for any sub-entities which don't have their own.
00124     ss << "Material";
00125     Ogre::MaterialPtr default_material = Ogre::MaterialManager::getSingleton().create( ss.str(), ROS_PACKAGE_NAME );
00126     default_material->setReceiveShadows(false);
00127     default_material->getTechnique(0)->setLightingEnabled(true);
00128     default_material->getTechnique(0)->setAmbient( 0.5, 0.5, 0.5 );
00129     materials_.insert( default_material );
00130 
00131     if ( new_message->mesh_use_embedded_materials )
00132     {
00133       // make clones of all embedded materials so selection works correctly
00134       S_MaterialPtr materials = getMaterials();
00135 
00136       S_MaterialPtr::iterator it;
00137       for ( it = materials.begin(); it!=materials.end(); it++ )
00138       {
00139         if( (*it)->getName() != "BaseWhiteNoLighting" )
00140         {
00141           Ogre::MaterialPtr new_material = (*it)->clone( id + (*it)->getName() );
00142           materials_.insert( new_material );
00143         }
00144       }
00145 
00146       // make sub-entities use cloned materials
00147       for (uint32_t i = 0; i < entity_->getNumSubEntities(); ++i)
00148       {
00149         std::string mat_name = entity_->getSubEntity(i)->getMaterialName();
00150         if( mat_name != "BaseWhiteNoLighting" )
00151         {
00152           entity_->getSubEntity(i)->setMaterialName( id + mat_name );
00153         }
00154         else
00155         {
00156           // BaseWhiteNoLighting is the default material Ogre uses
00157           // when it sees a mesh with no material.  Here we replace
00158           // that with our default_material which gets colored with
00159           // new_message->color.
00160           entity_->getSubEntity(i)->setMaterial( default_material );
00161         }
00162       }
00163     }
00164     else
00165     {
00166       entity_->setMaterial( default_material );
00167     }
00168 
00169     handler_.reset( new MarkerSelectionHandler( this, MarkerID( new_message->ns, new_message->id ), context_ ));
00170     handler_->addTrackedObject( entity_ );
00171   }
00172 
00173   if( need_color ||
00174       old_message->color.r != new_message->color.r ||
00175       old_message->color.g != new_message->color.g ||
00176       old_message->color.b != new_message->color.b ||
00177       old_message->color.a != new_message->color.a )
00178   {
00179     float r = new_message->color.r;
00180     float g = new_message->color.g;
00181     float b = new_message->color.b;
00182     float a = new_message->color.a;
00183 
00184     // Old way was to ignore the color and alpha when using embedded
00185     // materials, which meant you could leave them unset, which means
00186     // 0.  Since we now USE the color and alpha values, leaving them
00187     // all 0 will mean the object will be invisible.  Therefore detect
00188     // the situation where RGBA are all 0 and treat that the same as
00189     // all 1 (full white).
00190     if( new_message->mesh_use_embedded_materials && r == 0 && g == 0 && b == 0 && a == 0 )
00191     {
00192       r = 1; g = 1; b = 1; a = 1;
00193     }
00194 
00195     Ogre::SceneBlendType blending;
00196     bool depth_write;
00197 
00198     if ( a < 0.9998 )
00199     {
00200       blending = Ogre::SBT_TRANSPARENT_ALPHA;
00201       depth_write = false;
00202     }
00203     else
00204     {
00205       blending = Ogre::SBT_REPLACE;
00206       depth_write = true;
00207     }
00208 
00209     S_MaterialPtr::iterator it;
00210     for( it = materials_.begin(); it != materials_.end(); it++ )
00211     {
00212       Ogre::Technique* technique = (*it)->getTechnique( 0 );
00213 
00214       technique->setAmbient( r*0.5, g*0.5, b*0.5 );
00215       technique->setDiffuse( r, g, b, a );
00216       technique->setSceneBlending( blending );
00217       technique->setDepthWriteEnabled( depth_write );
00218       technique->setLightingEnabled( true );
00219     }
00220   }
00221 
00222   Ogre::Vector3 pos, scale;
00223   Ogre::Quaternion orient;
00224   transform(new_message, pos, orient, scale);
00225 
00226   scene_node_->setVisible(true);
00227   setPosition(pos);
00228   setOrientation(orient);
00229 
00230   scene_node_->setScale(scale);
00231 }
00232 
00233 S_MaterialPtr MeshResourceMarker::getMaterials()
00234 {
00235   S_MaterialPtr materials;
00236   if( entity_ )
00237   {
00238     extractMaterials( entity_, materials );
00239   }
00240   return materials;
00241 }
00242 
00243 }
00244 


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