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 <OgreSceneNode.h>
00041 #include <OgreSceneManager.h>
00042 #include <OgreEntity.h>
00043 #include <OgreSubEntity.h>
00044 #include <OgreMaterialManager.h>
00045 #include <OgreTextureManager.h>
00046 #include <OgreSharedPtr.h>
00047 #include <OgreTechnique.h>
00048 
00049 namespace rviz
00050 {
00051 
00052 MeshResourceMarker::MeshResourceMarker(MarkerDisplay* owner, DisplayContext* context, Ogre::SceneNode* parent_node)
00053 : MarkerBase(owner, context, parent_node)
00054 , entity_(0)
00055 {
00056 }
00057 
00058 MeshResourceMarker::~MeshResourceMarker()
00059 {
00060   reset();
00061 }
00062 
00063 void MeshResourceMarker::reset()
00064 {
00065   //destroy entity
00066   if (entity_)
00067   {
00068     context_->getSceneManager()->destroyEntity(entity_);
00069     entity_ = 0;
00070   }
00071 
00072 
00073   // destroy all the materials we've created
00074   S_MaterialPtr::iterator it;
00075   for (it = materials_.begin(); it != materials_.end(); it++)
00076   {
00077     Ogre::MaterialPtr material = *it;
00078     if (!material.isNull())
00079     {
00080       material->unload();
00081       Ogre::MaterialManager::getSingleton().remove(material->getName());
00082     }
00083   }
00084   materials_.clear();
00085   // the actual passes are deleted by the material
00086   color_tint_passes_.clear();
00087 }
00088 
00089 void MeshResourceMarker::onNewMessage(const MarkerConstPtr& old_message, const MarkerConstPtr& new_message)
00090 {
00091   ROS_ASSERT(new_message->type == visualization_msgs::Marker::MESH_RESOURCE);
00092 
00093   // flag indicating if the mesh material color needs to be updated
00094   bool update_color = false;
00095 
00096   scene_node_->setVisible(false);
00097 
00098   if (!entity_ ||
00099       old_message->mesh_resource != new_message->mesh_resource ||
00100       old_message->mesh_use_embedded_materials != new_message->mesh_use_embedded_materials)
00101   {
00102     reset();
00103 
00104     if (new_message->mesh_resource.empty())
00105     {
00106       return;
00107     }
00108 
00109     if (loadMeshFromResource(new_message->mesh_resource).isNull())
00110     {
00111       std::stringstream ss;
00112       ss << "Mesh resource marker [" << getStringID() << "] could not load [" << new_message->mesh_resource << "]";
00113       if (owner_)
00114       {
00115         owner_->setMarkerStatus(getID(), StatusProperty::Error, ss.str());
00116       }
00117       ROS_DEBUG("%s", ss.str().c_str());
00118       return;
00119     }
00120 
00121     static uint32_t count = 0;
00122     std::stringstream ss;
00123     ss << "mesh_resource_marker_" << count++;
00124     std::string id = ss.str();
00125     entity_ = context_->getSceneManager()->createEntity(id, new_message->mesh_resource);
00126     scene_node_->attachObject(entity_);
00127 
00128     // create a default material for any sub-entities which don't have their own.
00129     ss << "Material";
00130     Ogre::MaterialPtr default_material = Ogre::MaterialManager::getSingleton().create(ss.str(), ROS_PACKAGE_NAME);
00131     default_material->setReceiveShadows(false);
00132     default_material->getTechnique(0)->setLightingEnabled(true);
00133     default_material->getTechnique(0)->setAmbient(0.5, 0.5, 0.5);
00134     materials_.insert(default_material);
00135 
00136     if (new_message->mesh_use_embedded_materials)
00137     {
00138       // make clones of all embedded materials so selection works correctly
00139       S_MaterialPtr materials = getMaterials();
00140 
00141       S_MaterialPtr::iterator it;
00142       for (it = materials.begin(); it != materials.end(); it++)
00143       {
00144         if ((*it)->getName() != "BaseWhiteNoLighting")
00145         {
00146           Ogre::MaterialPtr new_material = (*it)->clone(id + (*it)->getName());
00147           materials_.insert(new_material);
00148         }
00149       }
00150 
00151       // make sub-entities use cloned materials
00152       for (uint32_t i = 0; i < entity_->getNumSubEntities(); ++i)
00153       {
00154         std::string mat_name = entity_->getSubEntity(i)->getMaterialName();
00155         if (mat_name != "BaseWhiteNoLighting")
00156         {
00157           entity_->getSubEntity(i)->setMaterialName(id + mat_name);
00158         }
00159         else
00160         {
00161           // BaseWhiteNoLighting is the default material Ogre uses
00162           // when it sees a mesh with no material.  Here we replace
00163           // that with our default_material which gets colored with
00164           // new_message->color.
00165           entity_->getSubEntity(i)->setMaterial(default_material);
00166         }
00167       }
00168     }
00169     else
00170     {
00171       entity_->setMaterial(default_material);
00172     }
00173 
00174     // add a pass to every material to perform the color tinting
00175     S_MaterialPtr::iterator material_it;
00176     for (material_it = materials_.begin(); material_it != materials_.end(); material_it++)
00177     {
00178       Ogre::Technique* technique = (*material_it)->getTechnique(0);
00179       color_tint_passes_.push_back(technique->createPass());
00180     }
00181 
00182     // always update color on resource change
00183     update_color = true;
00184 
00185     handler_.reset(new MarkerSelectionHandler(this, MarkerID(new_message->ns, new_message->id), context_));
00186     handler_->addTrackedObject(entity_);
00187   }
00188   else
00189   {
00190     // underlying mesh resource has not changed but if the color has
00191     //  then we need to update the materials color
00192     if (!old_message
00193         || old_message->color.r != new_message->color.r
00194         || old_message->color.g != new_message->color.g
00195         || old_message->color.b != new_message->color.b
00196         || old_message->color.a != new_message->color.a)
00197     {
00198       update_color = true;
00199     }
00200   }
00201 
00202   // update material color
00203   //  if the mesh_use_embedded_materials is true and color is non-zero
00204   //  then the color will be used to tint the embedded materials
00205   if (update_color)
00206   {
00207     float r = new_message->color.r;
00208     float g = new_message->color.g;
00209     float b = new_message->color.b;
00210     float a = new_message->color.a;
00211 
00212     Ogre::SceneBlendType blending;
00213     bool depth_write;
00214 
00215     if (a < 0.9998)
00216     {
00217       blending = Ogre::SBT_TRANSPARENT_ALPHA;
00218       depth_write = false;
00219     }
00220     else
00221     {
00222       blending = Ogre::SBT_REPLACE;
00223       depth_write = true;
00224     }
00225 
00226     for (std::vector<Ogre::Pass*>::iterator it = color_tint_passes_.begin();
00227          it != color_tint_passes_.end();
00228          ++it)
00229     {
00230       (*it)->setAmbient(0.5 * r, 0.5 * g, 0.5 * b);
00231       (*it)->setDiffuse(r, g, b, a);
00232       (*it)->setSceneBlending(blending);
00233       (*it)->setDepthWriteEnabled(depth_write);
00234       (*it)->setLightingEnabled(true);
00235     }
00236   }
00237 
00238   Ogre::Vector3 pos, scale;
00239   Ogre::Quaternion orient;
00240   transform(new_message, pos, orient, scale);
00241 
00242   scene_node_->setVisible(true);
00243   setPosition(pos);
00244   setOrientation(orient);
00245 
00246   scene_node_->setScale(scale);
00247 }
00248 
00249 S_MaterialPtr MeshResourceMarker::getMaterials()
00250 {
00251   S_MaterialPtr materials;
00252   if (entity_)
00253   {
00254     extractMaterials(entity_, materials);
00255   }
00256   return materials;
00257 }
00258 
00259 }
00260 


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Thu Aug 27 2015 15:02:27