00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include "stl_loader.h"
00031 #include <ros/console.h>
00032
00033 #include <OGRE/OgreManualObject.h>
00034
00035 namespace ogre_tools
00036 {
00037
00038 STLLoader::STLLoader()
00039 {
00040
00041 }
00042
00043 STLLoader::~STLLoader()
00044 {
00045
00046 }
00047
00048 bool STLLoader::load(const std::string& path)
00049 {
00050 FILE* input = fopen( path.c_str(), "r" );
00051 if ( !input )
00052 {
00053 ROS_ERROR( "Could not open '%s' for read", path.c_str() );
00054 return false;
00055 }
00056
00057
00058
00059
00060
00061
00062
00063
00064
00065
00066
00067
00068
00069
00070
00071
00072 fseek( input, 0, SEEK_END );
00073 long long fileSize = ftell( input );
00074 fseek( input, 0, SEEK_SET );
00075
00076 uint8_t* buffer = new uint8_t[ fileSize ];
00077 fread( buffer, fileSize, 1, input );
00078 fclose( input );
00079
00080 bool success = load(buffer);
00081 delete [] buffer;
00082
00083 return success;
00084 }
00085
00086 bool STLLoader::load(uint8_t* buffer)
00087 {
00088 uint8_t* pos = buffer;
00089 pos += 80;
00090
00091 unsigned int numTriangles = *(unsigned int*)pos;
00092 pos += 4;
00093
00094 for ( unsigned int currentTriangle = 0; currentTriangle < numTriangles; ++currentTriangle )
00095 {
00096 Triangle tri;
00097
00098 tri.normal_.x = *(float*)pos;
00099 pos += 4;
00100 tri.normal_.y = *(float*)pos;
00101 pos += 4;
00102 tri.normal_.z = *(float*)pos;
00103 pos += 4;
00104
00105 tri.vertices_[0].x = *(float*)pos;
00106 pos += 4;
00107 tri.vertices_[0].y = *(float*)pos;
00108 pos += 4;
00109 tri.vertices_[0].z = *(float*)pos;
00110 pos += 4;
00111
00112 tri.vertices_[1].x = *(float*)pos;
00113 pos += 4;
00114 tri.vertices_[1].y = *(float*)pos;
00115 pos += 4;
00116 tri.vertices_[1].z = *(float*)pos;
00117 pos += 4;
00118
00119 tri.vertices_[2].x = *(float*)pos;
00120 pos += 4;
00121 tri.vertices_[2].y = *(float*)pos;
00122 pos += 4;
00123 tri.vertices_[2].z = *(float*)pos;
00124 pos += 4;
00125
00126
00127
00128 pos += 2;
00129
00130
00131
00132 if (tri.normal_.squaredLength() < 0.001)
00133 {
00134 Ogre::Vector3 side1 = tri.vertices_[0] - tri.vertices_[1];
00135 Ogre::Vector3 side2 = tri.vertices_[1] - tri.vertices_[2];
00136 tri.normal_ = side1.crossProduct(side2);
00137 tri.normal_.normalise();
00138 }
00139
00140 triangles_.push_back(tri);
00141 }
00142
00143 return true;
00144 }
00145
00146 void calculateUV(const Ogre::Vector3& vec, float& u, float& v)
00147 {
00148 Ogre::Vector3 pos(vec);
00149 pos.normalise();
00150 u = acos( pos.y / pos.length() );
00151
00152 float val = pos.x / ( sin( u ) );
00153 v = acos( val );
00154
00155 u /= Ogre::Math::PI;
00156 v /= Ogre::Math::PI;
00157 }
00158
00159
00160 Ogre::MeshPtr STLLoader::toMesh(const std::string& name)
00161 {
00162 Ogre::ManualObject* object = new Ogre::ManualObject( "the one and only" );
00163 object->begin( "BaseWhiteNoLighting", Ogre::RenderOperation::OT_TRIANGLE_LIST );
00164
00165 unsigned int vertexCount = 0;
00166 V_Triangle::const_iterator it = triangles_.begin();
00167 V_Triangle::const_iterator end = triangles_.end();
00168 for (; it != end; ++it )
00169 {
00170 const STLLoader::Triangle& tri = *it;
00171
00172 float u, v;
00173 u = v = 0.0f;
00174 object->position( tri.vertices_[0] );
00175 object->normal( tri.normal_);
00176 calculateUV( tri.vertices_[0], u, v );
00177 object->textureCoord( u, v );
00178
00179 object->position( tri.vertices_[1] );
00180 object->normal( tri.normal_);
00181 calculateUV( tri.vertices_[1], u, v );
00182 object->textureCoord( u, v );
00183
00184 object->position( tri.vertices_[2] );
00185 object->normal( tri.normal_);
00186 calculateUV( tri.vertices_[2], u, v );
00187 object->textureCoord( u, v );
00188
00189 object->triangle( vertexCount + 0, vertexCount + 1, vertexCount + 2 );
00190
00191 vertexCount += 3;
00192 }
00193
00194 object->end();
00195
00196 Ogre::MeshPtr mesh = object->convertToMesh( name, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME );
00197 mesh->buildEdgeList();
00198
00199 delete object;
00200
00201 return mesh;
00202 }
00203
00204 }