stl_loader.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include "stl_loader.h"
31 #include <ros/console.h>
32 
33 #include <OgreManualObject.h>
34 
35 namespace ogre_tools
36 {
37 
39 {
40 
41 }
42 
44 {
45 
46 }
47 
48 bool STLLoader::load(const std::string& path)
49 {
50  FILE* input = fopen( path.c_str(), "r" );
51  if ( !input )
52  {
53  ROS_ERROR( "Could not open '%s' for read", path.c_str() );
54  return false;
55  }
56 
57  /* from wikipedia:
58  * Because ASCII STL files can become very large, a binary version of STL exists. A binary STL file has an 80 character header
59  * (which is generally ignored - but which should never begin with 'solid' because that will lead most software to assume that
60  * this is an ASCII STL file). Following the header is a 4 byte unsigned integer indicating the number of triangular facets in
61  * the file. Following that is data describing each triangle in turn. The file simply ends after the last triangle.
62  *
63  * Each triangle is described by twelve 32-bit-floating point numbers: three for the normal and then three for the X/Y/Z coordinate
64  * of each vertex - just as with the ASCII version of STL. After the twelve floats there is a two byte unsigned 'short' integer that
65  * is the 'attribute byte count' - in the standard format, this should be zero because most software does not understand anything else.
66  *
67  * Floating point numbers are represented as IEEE floating point numbers and the endianness is assumed to be little endian although this
68  * is not stated in documentation.
69  */
70 
71  // find the file size
72  fseek( input, 0, SEEK_END );
73  long fileSize = ftell( input );
74  rewind( input );
75 
76  std::vector<uint8_t> buffer_vec(fileSize);
77  uint8_t* buffer = &buffer_vec[0];
78 
79  long num_bytes_read = fread( buffer, 1, fileSize, input );
80  if ( num_bytes_read != fileSize )
81  {
82  ROS_ERROR("STLLoader::load( \"%s\" ) only read %ld bytes out of total %ld.",
83  path.c_str(), num_bytes_read, fileSize);
84  fclose( input );
85  return false;
86  }
87  fclose( input );
88 
89  return this->load(buffer, num_bytes_read, path);
90 }
91 
92 bool STLLoader::load(uint8_t* buffer, const size_t num_bytes, const std::string& origin)
93 {
94  // check for ascii since we can only load binary types with this class
95  std::string buffer_str = std::string(reinterpret_cast<char *>(buffer), num_bytes);
96 
97  if (buffer_str.substr(0, 5) == std::string("solid"))
98  {
99  // file says that it is ascii, but why should we trust it?
100 
101  // check for "endsolid" as well
102  if (buffer_str.find("endsolid", 5) != std::string::npos)
103  {
104  ROS_ERROR_STREAM("The STL file '" << origin << "' is malformed. It "
105  "starts with the word 'solid' and also contains the "
106  "word 'endsolid', indicating that it's an ASCII STL "
107  "file, but rviz can only load binary STL files so it "
108  "will not be loaded. Please convert it to a "
109  "binary STL file.");
110  return false;
111  }
112 
113  // chastise the user for malformed files
114  ROS_WARN_STREAM("The STL file '" << origin << "' is malformed. It starts "
115  "with the word 'solid', indicating that it's an ASCII "
116  "STL file, but it does not contain the word 'endsolid' so "
117  "it is either a malformed ASCII STL file or it is actually "
118  "a binary STL file. Trying to interpret it as a binary "
119  "STL file instead.");
120  }
121 
122  // make sure there's enough data for a binary STL header and triangle count
123  static const size_t binary_stl_header_len = 84;
124  if (num_bytes <= binary_stl_header_len)
125  {
126  ROS_ERROR_STREAM("The STL file '" << origin << "' is malformed. It "
127  "appears to be a binary STL file but does not contain "
128  "enough data for the 80 byte header and 32-bit integer "
129  "triangle count.");
130  return false;
131  }
132 
133  // one last check to make sure that the size matches the number of triangles
134  unsigned int num_triangles = *(reinterpret_cast<uint32_t *>(buffer + 80));
135  static const size_t number_of_bytes_per_triangle = 50;
136  size_t expected_size = binary_stl_header_len + num_triangles * number_of_bytes_per_triangle;
137  if (num_bytes < expected_size)
138  {
139  ROS_ERROR_STREAM("The STL file '" << origin << "' is malformed. According "
140  "to the binary STL header it should have '" <<
141  num_triangles << "' triangles, but it has too little" <<
142  " data for that to be the case.");
143  return false;
144  }
145  else if (num_bytes > expected_size)
146  {
147  ROS_WARN_STREAM("The STL file '" << origin << "' is malformed. According "
148  "to the binary STL header it should have '" <<
149  num_triangles << "' triangles, but it has too much" <<
150  " data for that to be the case. The extra data will be" <<
151  " ignored.");
152  }
153 
154  // load the binary STL data
155  return this->load_binary(buffer);
156 }
157 
158 bool STLLoader::load_binary(uint8_t* buffer)
159 {
160  uint8_t* pos = buffer;
161 
162  pos += 80; // skip the 80 byte header
163 
164  unsigned int numTriangles = *(unsigned int*)pos;
165  pos += 4;
166 
167  for ( unsigned int currentTriangle = 0; currentTriangle < numTriangles; ++currentTriangle )
168  {
169  Triangle tri;
170 
171  tri.normal_.x = *(float*)pos;
172  pos += 4;
173  tri.normal_.y = *(float*)pos;
174  pos += 4;
175  tri.normal_.z = *(float*)pos;
176  pos += 4;
177 
178  tri.vertices_[0].x = *(float*)pos;
179  pos += 4;
180  tri.vertices_[0].y = *(float*)pos;
181  pos += 4;
182  tri.vertices_[0].z = *(float*)pos;
183  pos += 4;
184 
185  tri.vertices_[1].x = *(float*)pos;
186  pos += 4;
187  tri.vertices_[1].y = *(float*)pos;
188  pos += 4;
189  tri.vertices_[1].z = *(float*)pos;
190  pos += 4;
191 
192  tri.vertices_[2].x = *(float*)pos;
193  pos += 4;
194  tri.vertices_[2].y = *(float*)pos;
195  pos += 4;
196  tri.vertices_[2].z = *(float*)pos;
197  pos += 4;
198 
199  // Blender was writing a large number into this short... am I misinterpreting what the attribute byte count is supposed to do?
200  //unsigned short attributeByteCount = *(unsigned short*)pos;
201  pos += 2;
202 
203  //pos += attributeByteCount;
204 
205  if (tri.normal_.squaredLength() < 0.001)
206  {
207  Ogre::Vector3 side1 = tri.vertices_[0] - tri.vertices_[1];
208  Ogre::Vector3 side2 = tri.vertices_[1] - tri.vertices_[2];
209  tri.normal_ = side1.crossProduct(side2);
210  }
211  tri.normal_.normalise();
212 
213  triangles_.push_back(tri);
214  }
215 
216  return true;
217 }
218 
219 void calculateUV(const Ogre::Vector3& vec, float& u, float& v)
220 {
221  Ogre::Vector3 pos(vec);
222  pos.normalise();
223  u = acos( pos.y / pos.length() );
224 
225  float val = pos.x / ( sin( u ) );
226  v = acos( val );
227 
228  u /= Ogre::Math::PI;
229  v /= Ogre::Math::PI;
230 }
231 
232 
233 Ogre::MeshPtr STLLoader::toMesh(const std::string& name)
234 {
235  Ogre::ManualObject* object = new Ogre::ManualObject( "the one and only" );
236  object->begin( "BaseWhiteNoLighting", Ogre::RenderOperation::OT_TRIANGLE_LIST );
237 
238  unsigned int vertexCount = 0;
239  V_Triangle::const_iterator it = triangles_.begin();
240  V_Triangle::const_iterator end = triangles_.end();
241  for (; it != end; ++it )
242  {
243  if( vertexCount >= 2004 )
244  {
245  // Subdivide large meshes into submeshes with at most 2004
246  // vertices to prevent problems on some graphics cards.
247  object->end();
248  object->begin( "BaseWhiteNoLighting", Ogre::RenderOperation::OT_TRIANGLE_LIST );
249  vertexCount = 0;
250  }
251 
252  const STLLoader::Triangle& tri = *it;
253 
254  float u, v;
255  u = v = 0.0f;
256  object->position( tri.vertices_[0] );
257  object->normal( tri.normal_);
258  calculateUV( tri.vertices_[0], u, v );
259  object->textureCoord( u, v );
260 
261  object->position( tri.vertices_[1] );
262  object->normal( tri.normal_);
263  calculateUV( tri.vertices_[1], u, v );
264  object->textureCoord( u, v );
265 
266  object->position( tri.vertices_[2] );
267  object->normal( tri.normal_);
268  calculateUV( tri.vertices_[2], u, v );
269  object->textureCoord( u, v );
270 
271  object->triangle( vertexCount + 0, vertexCount + 1, vertexCount + 2 );
272 
273  vertexCount += 3;
274  }
275 
276  object->end();
277 
278  Ogre::MeshPtr mesh = object->convertToMesh( name, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME );
279  mesh->buildEdgeList();
280 
281  delete object;
282 
283  return mesh;
284 }
285 
286 }
V_Triangle triangles_
Definition: stl_loader.h:60
bool load_binary(uint8_t *buffer)
Load a binary STL file.
Definition: stl_loader.cpp:158
void calculateUV(const Ogre::Vector3 &vec, float &u, float &v)
Definition: stl_loader.cpp:219
bool load(const std::string &path)
Definition: stl_loader.cpp:48
Ogre::Vector3 vertices_[3]
Definition: stl_loader.h:55
#define ROS_WARN_STREAM(args)
Ogre::MeshPtr toMesh(const std::string &name)
Definition: stl_loader.cpp:233
#define ROS_ERROR_STREAM(args)
#define ROS_ERROR(...)


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat Apr 27 2019 02:33:42