$search
00001 /* 00002 * Copyright (c) 2011, 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 "rviz_interaction_tools/mesh_object.h" 00031 00032 #include <OGRE/OgreMesh.h> 00033 #include <OGRE/OgreManualObject.h> 00034 #include <OGRE/OgreMaterialManager.h> 00035 #include <OGRE/OgreSceneNode.h> 00036 #include <OGRE/OgreSceneManager.h> 00037 #include <OGRE/OgreEntity.h> 00038 #include <OGRE/OgreMeshManager.h> 00039 00040 namespace rviz_interaction_tools 00041 { 00042 00043 MeshObject::MeshObject( Ogre::SceneManager* scene_manager, Ogre::SceneNode* scene_root ) : 00044 entity_(0), 00045 scene_manager_(scene_manager), 00046 scene_root_(scene_root) 00047 { 00048 scene_node_ = scene_root->createChildSceneNode(); 00049 } 00050 00051 MeshObject::~MeshObject() 00052 { 00053 clear(); 00054 scene_root_->removeChild(scene_node_); 00055 } 00056 00057 void MeshObject::clear( ) 00058 { 00059 scene_node_->detachAllObjects(); 00060 00061 if ( entity_ ) 00062 { 00063 scene_manager_->destroyEntity(entity_); 00064 entity_ = 0; 00065 } 00066 00067 if ( !mesh_ptr_.isNull() ) 00068 { 00069 Ogre::MeshManager::getSingleton().remove( mesh_ptr_->getHandle() ); 00070 mesh_ptr_.setNull(); 00071 } 00072 } 00073 00074 void MeshObject::setVisible( bool visible ) 00075 { 00076 entity_->setVisible( visible ); 00077 entity_->setQueryFlags( visible ? 1 : 0 ); 00078 } 00079 00080 void MeshObject::setMaterialName( std::string name ) 00081 { 00082 entity_->setMaterialName(name); 00083 } 00084 00085 void MeshObject::setPose( const geometry_msgs::Pose& pose ) 00086 { 00087 scene_node_->setPosition( pose.position.x, pose.position.y, pose.position.z ); 00088 scene_node_->setOrientation( pose.orientation.w, pose.orientation.x, pose.orientation.y, pose.orientation.z ); 00089 } 00090 00091 void MeshObject::loadMesh( std::string name, const arm_navigation_msgs::Shape& mesh ) 00092 { 00093 ROS_ASSERT(mesh.triangles.size() % 3 == 0); 00094 ROS_ASSERT(mesh.triangles.size() > 0); 00095 ROS_ASSERT(mesh.vertices.size() > 0); 00096 00097 ROS_INFO_STREAM( "Loading mesh. name='" << name << "'" ); 00098 00099 //create ogre object 00100 Ogre::ManualObject *manual_object = new Ogre::ManualObject( name ); 00101 00102 manual_object->setUseIdentityProjection(false); 00103 manual_object->setUseIdentityView(false); 00104 manual_object->setDynamic(true); 00105 00106 manual_object->estimateVertexCount( mesh.vertices.size() ); 00107 manual_object->estimateIndexCount( mesh.triangles.size()*3 ); 00108 00109 manual_object->begin( "BaseWhiteNoLighting", Ogre::RenderOperation::OT_TRIANGLE_LIST ); 00110 00111 //add vertices 00112 for ( size_t v=0; v<mesh.vertices.size(); ++v ) 00113 { 00114 const geometry_msgs::Point& p = mesh.vertices[v]; 00115 manual_object->position( p.x, p.y, p.z ); 00116 manual_object->colour( 1.0, 1.0, 1.0, 1.0 ); 00117 } 00118 00119 //add triangles 00120 size_t num_t = mesh.triangles.size(); 00121 for ( size_t t=0; t+2<num_t; t+=3 ) 00122 { 00123 assert( (size_t)mesh.triangles[t] < mesh.vertices.size() ); 00124 assert( (size_t)mesh.triangles[t+1] < mesh.vertices.size() ); 00125 assert( (size_t)mesh.triangles[t+2] < mesh.vertices.size() ); 00126 00127 manual_object->triangle( mesh.triangles[t+2], mesh.triangles[t+1], mesh.triangles[t] ); 00128 } 00129 00130 manual_object->end(); 00131 00132 std::string mesh_name = name + "mesh"; 00133 00134 Ogre::MeshPtr mesh_ptr = manual_object->convertToMesh( mesh_name, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME ); 00135 mesh_ptr->buildEdgeList(); 00136 00137 entity_ = scene_manager_->createEntity( name, mesh_name ); 00138 entity_->setRenderQueueGroup(Ogre::RENDER_QUEUE_1); 00139 00140 scene_node_->attachObject( entity_ ); 00141 00142 delete manual_object; 00143 00144 mesh_ptr_ = mesh_ptr; 00145 } 00146 00147 void MeshObject::loadPoints( std::string name, const std::vector< geometry_msgs::Point32 > &points ) 00148 { 00149 std::vector< Point > points_converted; 00150 points_converted.reserve( points.size() ); 00151 00152 Point point; 00153 point.r = point.g = point.b = 0; 00154 00155 for ( unsigned i=0; i<points.size(); i++ ) 00156 { 00157 point.x = points[i].x; 00158 point.y = points[i].y; 00159 point.z = points[i].z; 00160 point.a = 1.0; 00161 points_converted.push_back( point ); 00162 } 00163 00164 loadMesh( name, points_converted ); 00165 } 00166 00167 void MeshObject::loadMesh( std::string name, const std::vector< Point > &vertices, 00168 const std::vector<unsigned> triangles ) 00169 { 00170 ROS_ASSERT(vertices.size() > 0); 00171 00172 //create ogre object 00173 Ogre::ManualObject *manual_object = new Ogre::ManualObject( name ); 00174 00175 manual_object->setUseIdentityProjection(false); 00176 manual_object->setUseIdentityView(false); 00177 manual_object->setDynamic(true); 00178 00179 manual_object->estimateVertexCount( vertices.size() ); 00180 manual_object->estimateIndexCount( triangles.size() > 0 ? triangles.size() : vertices.size()*3 ); 00181 00182 manual_object->begin( "BaseWhiteNoLighting", Ogre::RenderOperation::OT_TRIANGLE_LIST ); 00183 00184 //add vertices 00185 for ( size_t v=0; v<vertices.size(); ++v ) 00186 { 00187 const Point& p = vertices[v]; 00188 manual_object->position( p.x, p.y, p.z ); 00189 manual_object->colour( p.r, p.g, p.b ); 00190 } 00191 00192 //add triangles 00193 if ( triangles.size() > 0 ) 00194 { 00195 size_t num_t = triangles.size(); 00196 for ( size_t t=0; t+2<num_t; t+=3 ) 00197 { 00198 assert( (size_t)triangles[t] < vertices.size() ); 00199 assert( (size_t)triangles[t+1] < vertices.size() ); 00200 assert( (size_t)triangles[t+2] < vertices.size() ); 00201 00202 manual_object->triangle( triangles[t], triangles[t+1], triangles[t+2] ); 00203 } 00204 } 00205 else 00206 { 00207 for ( size_t t=0; t<vertices.size(); t+=3 ) 00208 { 00209 manual_object->triangle( t, (t+1)%vertices.size(), (t+2)%vertices.size() ); 00210 } 00211 } 00212 00213 manual_object->end(); 00214 00215 std::string mesh_name = name + "mesh"; 00216 00217 Ogre::MeshPtr mesh_ptr = manual_object->convertToMesh( mesh_name, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME ); 00218 mesh_ptr->buildEdgeList(); 00219 00220 entity_ = scene_manager_->createEntity( name, mesh_name ); 00221 entity_->setRenderQueueGroup(Ogre::RENDER_QUEUE_1); 00222 entity_->setCastShadows(false); 00223 00224 scene_node_->attachObject( entity_ ); 00225 00226 delete manual_object; 00227 00228 mesh_ptr_ = mesh_ptr; 00229 00230 #if 0 00231 Ogre::Vector3 min = entity_->getBoundingBox().getMinimum(); 00232 Ogre::Vector3 max = entity_->getBoundingBox().getMaximum(); 00233 ROS_INFO("Bbox min: %f %f %f max: %f %f %f", 00234 min.x, min.y, min.z, max.x, max.y, max.z ); 00235 #endif 00236 } 00237 00238 }