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   scene_node_->setVisible(false);
00100 
00101   if (!entity_ || old_message->mesh_resource != new_message->mesh_resource)
00102   {
00103     reset();
00104 
00105     if (new_message->mesh_resource.empty())
00106     {
00107       return;
00108     }
00109 
00110     if (loadMeshFromResource(new_message->mesh_resource).isNull())
00111     {
00112       std::stringstream ss;
00113       ss << "Mesh resource marker [" << getStringID() << "] could not load [" << new_message->mesh_resource << "]";
00114       if ( owner_ )
00115       {
00116         owner_->setMarkerStatus(getID(), status_levels::Error, ss.str());
00117       }
00118       ROS_DEBUG("%s", ss.str().c_str());
00119       return;
00120     }
00121 
00122     static uint32_t count = 0;
00123     std::stringstream ss;
00124     ss << "mesh_resource_marker_" << count++;
00125     std::string id = ss.str();
00126     entity_ = vis_manager_->getSceneManager()->createEntity(id, new_message->mesh_resource);
00127     scene_node_->attachObject(entity_);
00128 
00129     if ( new_message->mesh_use_embedded_materials )
00130     {
00131       // make clones of all embedded materials so selection works correctly
00132       S_MaterialPtr materials = getMaterials();
00133 
00134       S_MaterialPtr::iterator it;
00135       for ( it = materials.begin(); it!=materials.end(); it++ )
00136       {
00137         Ogre::MaterialPtr new_material = (*it)->clone( id + (*it)->getName() );
00138         materials_.insert( new_material );
00139       }
00140 
00141       // make sub-entities use cloned materials
00142       for (uint32_t i = 0; i < entity_->getNumSubEntities(); ++i)
00143       {
00144         std::string mat_name = entity_->getSubEntity(i)->getMaterialName();
00145         entity_->getSubEntity(i)->setMaterialName( id + mat_name );
00146       }
00147     }
00148     else
00149     {
00150       // create a new single material for all the sub-entities
00151       ss << "Material";
00152       Ogre::MaterialPtr material = Ogre::MaterialManager::getSingleton().create( ss.str(), ROS_PACKAGE_NAME );
00153       material->setReceiveShadows(false);
00154       material->getTechnique(0)->setLightingEnabled(true);
00155       material->getTechnique(0)->setAmbient( 0.5, 0.5, 0.5 );
00156 
00157       float r = new_message->color.r;
00158       float g = new_message->color.g;
00159       float b = new_message->color.b;
00160       float a = new_message->color.a;
00161       material->getTechnique(0)->setAmbient( r*0.5, g*0.5, b*0.5 );
00162       material->getTechnique(0)->setDiffuse( r, g, b, a );
00163 
00164       if ( a < 0.9998 )
00165       {
00166         material->getTechnique(0)->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA );
00167         material->getTechnique(0)->setDepthWriteEnabled( false );
00168       }
00169       else
00170       {
00171         material->getTechnique(0)->setSceneBlending( Ogre::SBT_REPLACE );
00172         material->getTechnique(0)->setDepthWriteEnabled( true );
00173       }
00174       entity_->setMaterial( material );
00175       materials_.insert( material );
00176     }
00177 
00178     vis_manager_->getSelectionManager()->removeObject(coll_);
00179     coll_ = vis_manager_->getSelectionManager()->createCollisionForEntity(entity_, SelectionHandlerPtr(new MarkerSelectionHandler(this, MarkerID(new_message->ns, new_message->id))), coll_);
00180   }
00181 
00182   Ogre::Vector3 pos, scale;
00183   Ogre::Quaternion orient;
00184   transform(new_message, pos, orient, scale);
00185 
00186   scene_node_->setVisible(true);
00187   setPosition(pos);
00188   setOrientation(orient);
00189   scene_node_->setScale(scale);
00190 }
00191 
00192 S_MaterialPtr MeshResourceMarker::getMaterials()
00193 {
00194   S_MaterialPtr materials;
00195   extractMaterials( entity_, materials );
00196   return materials;
00197 }
00198 
00199 }
00200 


rviz_qt
Author(s): Dave Hershberger
autogenerated on Fri Dec 6 2013 20:56:52