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 
00086 }
00087 
00088 void MeshResourceMarker::onNewMessage(const MarkerConstPtr& old_message, const MarkerConstPtr& new_message)
00089 {
00090   ROS_ASSERT(new_message->type == visualization_msgs::Marker::MESH_RESOURCE);
00091 
00092   // flag indicating if the mesh material color needs to be updated
00093   bool update_color = false;
00094 
00095   scene_node_->setVisible(false);
00096 
00097   // Get the color information from the message
00098   float r = new_message->color.r;
00099   float g = new_message->color.g;
00100   float b = new_message->color.b;
00101   float a = new_message->color.a;
00102 
00103   Ogre::SceneBlendType blending;
00104   bool depth_write;
00105 
00106   if (a < 0.9998)
00107   {
00108     blending = Ogre::SBT_TRANSPARENT_ALPHA;
00109     depth_write = false;
00110   }
00111   else
00112   {
00113     blending = Ogre::SBT_REPLACE;
00114     depth_write = true;
00115   }
00116 
00117 
00118   if (!entity_ ||
00119       old_message->mesh_resource != new_message->mesh_resource ||
00120       old_message->mesh_use_embedded_materials != new_message->mesh_use_embedded_materials)
00121   {
00122     reset();
00123 
00124     if (new_message->mesh_resource.empty())
00125     {
00126       return;
00127     }
00128 
00129     if (loadMeshFromResource(new_message->mesh_resource).isNull())
00130     {
00131       std::stringstream ss;
00132       ss << "Mesh resource marker [" << getStringID() << "] could not load [" << new_message->mesh_resource << "]";
00133       if (owner_)
00134       {
00135         owner_->setMarkerStatus(getID(), StatusProperty::Error, ss.str());
00136       }
00137       ROS_DEBUG("%s", ss.str().c_str());
00138       return;
00139     }
00140 
00141     static uint32_t count = 0;
00142     std::stringstream ss;
00143     ss << "mesh_resource_marker_" << count++;
00144     std::string id = ss.str();
00145     entity_ = context_->getSceneManager()->createEntity(id, new_message->mesh_resource);
00146     scene_node_->attachObject(entity_);
00147     
00148     // create a default material for any sub-entities which don't have their own.
00149     ss << "Material";
00150     Ogre::MaterialPtr default_material = Ogre::MaterialManager::getSingleton().create(ss.str(), ROS_PACKAGE_NAME);
00151     default_material->setReceiveShadows(false);
00152     default_material->getTechnique(0)->setLightingEnabled(true);
00153     default_material->getTechnique(0)->setAmbient(0.5, 0.5, 0.5);
00154 
00155     materials_.insert(default_material);
00156 
00157     if (new_message->mesh_use_embedded_materials)
00158     {
00159       // make clones of all embedded materials so selection works correctly
00160       S_MaterialPtr materials = getMaterials();
00161 
00162       S_MaterialPtr::iterator it;
00163       for (it = materials.begin(); it != materials.end(); it++)
00164       {
00165         if ((*it)->getName() != "BaseWhiteNoLighting")
00166         {
00167           Ogre::MaterialPtr new_material = (*it)->clone(id + (*it)->getName());
00168           materials_.insert(new_material);
00169         }
00170       }
00171 
00172       // make sub-entities use cloned materials
00173       for (uint32_t i = 0; i < entity_->getNumSubEntities(); ++i)
00174       {
00175         std::string mat_name = entity_->getSubEntity(i)->getMaterialName();
00176         if (mat_name != "BaseWhiteNoLighting")
00177         {
00178           entity_->getSubEntity(i)->setMaterialName(id + mat_name);
00179         }
00180         else
00181         {
00182           // BaseWhiteNoLighting is the default material Ogre uses
00183           // when it sees a mesh with no material.  Here we replace
00184           // that with our default_material which gets colored with
00185           // new_message->color.
00186           entity_->getSubEntity(i)->setMaterial(default_material);
00187         }
00188       }
00189     }
00190     else
00191     {
00192       entity_->setMaterial(default_material);
00193     }
00194 
00195     update_color = true;
00196 
00197     handler_.reset(new MarkerSelectionHandler(this, MarkerID(new_message->ns, new_message->id), context_));
00198     handler_->addTrackedObject(entity_);
00199   }
00200   else
00201   {
00202     // underlying mesh resource has not changed but if the color has
00203     //  then we need to update the materials color
00204     if (new_message->mesh_use_embedded_materials == false
00205        && (!old_message
00206         || old_message->mesh_use_embedded_materials == true
00207         || old_message->color.r != new_message->color.r
00208         || old_message->color.g != new_message->color.g
00209         || old_message->color.b != new_message->color.b
00210         || old_message->color.a != new_message->color.a))
00211     {
00212       update_color = true;
00213     }
00214   }
00215 
00216   // update material color
00217   //  if the mesh_use_embedded_materials is true and color is non-zero
00218   //  then the color will be used to tint the embedded materials
00219   if (update_color)
00220   { 
00221     if( new_message->mesh_use_embedded_materials && r == 0 && g == 0 && b == 0 && a == 0 )
00222     {
00223     blending = Ogre::SBT_REPLACE;
00224     depth_write = true;
00225     r = 1; g = 1; b = 1; a = 1;
00226     }
00227     S_MaterialPtr::iterator material_it;
00228     for (material_it = materials_.begin(); material_it != materials_.end(); material_it++)
00229     {
00230       Ogre::Technique* technique = (*material_it)->getTechnique(0);
00231       technique->setAmbient( r*0.5, g*0.5, b*0.5 );
00232       technique->setDiffuse( r, g, b, a );
00233       technique->setSceneBlending( blending );
00234       technique->setDepthWriteEnabled( depth_write );
00235       technique->setLightingEnabled( true );
00236     }
00237    
00238   }
00239 
00240   Ogre::Vector3 pos, scale;
00241   Ogre::Quaternion orient;
00242   transform(new_message, pos, orient, scale);
00243 
00244   scene_node_->setVisible(true);
00245   setPosition(pos);
00246   setOrientation(orient);
00247 
00248   scene_node_->setScale(scale);
00249 }
00250 
00251 S_MaterialPtr MeshResourceMarker::getMaterials()
00252 {
00253   S_MaterialPtr materials;
00254   if (entity_)
00255   {
00256     extractMaterials(entity_, materials);
00257   }
00258   return materials;
00259 }
00260 
00261 }


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Thu Jun 6 2019 18:02:15