material.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/material.h>
00031 #include <rve_render_server/renderable.h>
00032 #include <rve_render_server/ogre_material_generator.h>
00033 
00034 #include <OGRE/OgreMaterialManager.h>
00035 #include <OGRE/OgreTextureManager.h>
00036 #include <OGRE/OgreTexture.h>
00037 #include <OGRE/OgreTechnique.h>
00038 #include <OGRE/OgreImage.h>
00039 #include <OGRE/OgreRenderable.h>
00040 
00041 #include <resource_retriever/retriever.h>
00042 
00043 #include <boost/filesystem.hpp>
00044 namespace fs = boost::filesystem;
00045 
00046 namespace rve_render_server
00047 {
00048 
00049 void Material::setMaterial(const rve_msgs::Material& mat)
00050 {
00051   input_material_ = mat;
00052   createMaterialFromInput();
00053   materialUpdated();
00054 }
00055 
00056 void Material::createMaterialFromInput()
00057 {
00058   Ogre::MaterialPtr old_mat = material_;
00059 
00060   material_ = generateOgreMaterial(input_material_);
00061 
00062   if (old_mat != material_)
00063   {
00064     ogreMaterialChanged();
00065   }
00066 }
00067 
00068 void Material::ogreMaterialChanged()
00069 {
00070   M_Renderable::iterator it = rends_.begin();
00071   M_Renderable::iterator end = rends_.end();
00072   for (; it != end; ++it)
00073   {
00074     Renderable* rend = it->first;
00075     rend->onOgreMaterialChanged(shared_from_this());
00076   }
00077 }
00078 
00079 void Material::materialUpdated()
00080 {
00081   M_Renderable::iterator it = rends_.begin();
00082   M_Renderable::iterator end = rends_.end();
00083   for (; it != end; ++it)
00084   {
00085     V_OgreRenderable::iterator og_it = it->second.begin();
00086     V_OgreRenderable::iterator og_end = it->second.end();
00087     for (; og_it != og_end; ++og_it)
00088     {
00089       Ogre::Renderable* ogre_rend = *og_it;
00090       ogre_rend->setCustomParameter(CustomParam_Color, Ogre::Vector4(input_material_.color.r, input_material_.color.g, input_material_.color.b, input_material_.opacity));
00091     }
00092   }
00093 }
00094 
00095 void Material::attachRenderable(Renderable* rend, Ogre::Renderable* ogre_rend)
00096 {
00097   rends_[rend].push_back(ogre_rend);
00098 
00099   onRenderableAttached(rend, ogre_rend);
00100 }
00101 
00102 void Material::detachRenderable(Renderable* rend, Ogre::Renderable* ogre_rend)
00103 {
00104   M_Renderable::iterator it = rends_.find(rend);
00105   if (it != rends_.end())
00106   {
00107     V_OgreRenderable& ogre_rends = it->second;
00108     std::remove(ogre_rends.begin(), ogre_rends.end(), ogre_rend);
00109     ogre_rends.pop_back();
00110 
00111     if (ogre_rends.empty())
00112     {
00113       rends_.erase(it);
00114     }
00115 
00116     onRenderableDetached(rend, ogre_rend);
00117   }
00118 }
00119 
00120 void Material::detachRenderable(Renderable* rend)
00121 {
00122   M_Renderable::iterator it = rends_.find(rend);
00123   if (it != rends_.end())
00124   {
00125     rends_.erase(it);
00126     onRenderableDetached(rend, 0);
00127   }
00128 }
00129 
00130 void Material::onRenderableAttached(Renderable* rend, Ogre::Renderable* ogre_rend)
00131 {
00132   rend->onOgreMaterialChanged(shared_from_this());
00133   ogre_rend->setCustomParameter(CustomParam_Color, Ogre::Vector4(input_material_.color.r, input_material_.color.g, input_material_.color.b, input_material_.opacity));
00134 }
00135 
00136 void Material::onRenderableDetached(Renderable* rend, Ogre::Renderable* ogre_rend)
00137 {
00138 }
00139 
00140 } // namespace rve_render_server
00141 
00142 


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