mesh_instance.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/mesh_instance.h>
00031 #include <rve_render_server/mesh.h>
00032 #include <rve_render_server/submesh.h>
00033 #include <rve_render_server/material.h>
00034 #include <rve_render_server/init.h>
00035 #include <rve_render_server/renderer.h>
00036 
00037 #include <OGRE/OgreSceneManager.h>
00038 #include <OGRE/OgreEntity.h>
00039 #include <OGRE/OgreSubEntity.h>
00040 #include <OGRE/OgreSceneNode.h>
00041 
00042 #include <ros/types.h>
00043 #include <ros/console.h>
00044 #include <ros/assert.h>
00045 
00046 namespace rve_render_server
00047 {
00048 
00049 MeshInstance::MeshInstance(const rve_common::UUID& id, Ogre::SceneManager* scene_manager, const MeshPtr& mesh)
00050 : Renderable(id)
00051 , scene_manager_(scene_manager)
00052 , mesh_(mesh)
00053 {
00054   std::stringstream ss;
00055   static size_t count = 0;
00056   ss << "MeshInstance" << count++;
00057 
00058   entity_ = scene_manager_->createEntity(ss.str(), mesh->getID().toString());
00059   scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00060   scene_node_->attachObject(entity_);
00061 
00062   pick_id_ = getRenderer()->allocatePickID(this);
00063   Ogre::Vector4 pick_color(intToFloat4<Ogre::Vector4>(pick_id_));
00064 
00065   for (size_t i = 0; i < mesh->getSubMeshCount(); ++i)
00066   {
00067     rve_common::UUID mat_id = mesh->getSubMesh(i)->getMaterialID();
00068     entity_->getSubEntity(i)->setCustomParameter(Material::CustomParam_ObjectID, pick_color);
00069 
00070     if (!mat_id.isNull())
00071     {
00072       MaterialPtr mat = getRenderer()->getMaterial(mat_id);
00073       setMaterial(i, mat);
00074     }
00075   }
00076 }
00077 
00078 MeshInstance::~MeshInstance()
00079 {
00080   M_Material::iterator it = mat_to_subs_.begin();
00081   M_Material::iterator end = mat_to_subs_.end();
00082   for (; it != end; ++it)
00083   {
00084     it->first->detachRenderable(this);
00085   }
00086 
00087   scene_manager_->destroyEntity(entity_);
00088   scene_manager_->destroySceneNode(scene_node_);
00089 
00090   getRenderer()->deallocatePickID(pick_id_);
00091 }
00092 
00093 void MeshInstance::setMaterial(const MaterialPtr& mat)
00094 {
00095   M_Material::iterator it = mat_to_subs_.begin();
00096   M_Material::iterator end = mat_to_subs_.end();
00097   for (; it != end; ++it)
00098   {
00099     it->first->detachRenderable(this);
00100   }
00101 
00102   mat_to_subs_.clear();
00103 
00104   if (mat)
00105   {
00106     for (uint32_t i = 0; i < entity_->getNumSubEntities(); ++i)
00107     {
00108       Ogre::SubEntity* sub = entity_->getSubEntity(i);
00109       mat_to_subs_[mat].insert(sub);
00110       sub_to_mat_[sub] = mat;
00111 
00112       mat->attachRenderable(this, sub);
00113     }
00114   }
00115 }
00116 
00117 void MeshInstance::setMaterial(size_t submesh_index, const MaterialPtr& mat)
00118 {
00119   ROS_ASSERT(submesh_index < entity_->getNumSubEntities());
00120   Ogre::SubEntity* sub = entity_->getSubEntity(submesh_index);
00121   M_SubEntityToMaterial::iterator subent_it = sub_to_mat_.find(sub);
00122   if (subent_it != sub_to_mat_.end())
00123   {
00124     const MaterialPtr& old_mat = subent_it->second;
00125     mat_to_subs_[old_mat].erase(sub);
00126   }
00127 
00128   sub_to_mat_[sub] = mat;
00129   mat_to_subs_[mat].insert(sub);
00130   mat->attachRenderable(this, sub);
00131 }
00132 
00133 void MeshInstance::onOgreMaterialChanged(const MaterialPtr& mat)
00134 {
00135   M_Material::iterator it = mat_to_subs_.find(mat);
00136   if (it != mat_to_subs_.end())
00137   {
00138     const MaterialPtr& mat = it->first;
00139     S_OgreSubEntity::iterator sub_it = it->second.begin();
00140     S_OgreSubEntity::iterator sub_end = it->second.end();
00141     for (; sub_it != sub_end; ++sub_it)
00142     {
00143       Ogre::SubEntity* sub = *sub_it;
00144       sub->setMaterial(mat->getOgreMaterial());
00145     }
00146   }
00147 }
00148 
00149 Picked MeshInstance::translatePick(PickRenderValues id)
00150 {
00151   ROS_ASSERT(id.id == pick_id_);
00152   return Picked(getID(), 0);
00153 }
00154 
00155 } // namespace rve_render_server


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