From 6285603c53616733fec062619094516d5e8fc838 Mon Sep 17 00:00:00 2001 From: kwc Date: Fri, 4 Sep 2009 23:10:08 +0000 Subject: [PATCH] migration part 1 --- CMakeLists.txt | 19 + Makefile | 1 + .../ConvexDecomposition.cpp | 1065 + .../ConvexDecomposition/ConvexDecomposition.h | 249 + .../ConvexDecomposition/bestfit.cpp | 483 + .../ConvexDecomposition/bestfit.h | 90 + .../ConvexDecomposition/bestfitobb.cpp | 368 + .../ConvexDecomposition/bestfitobb.h | 100 + .../ConvexDecomposition/cd_hull.cpp | 3650 ++++ .../ConvexDecomposition/cd_hull.h | 250 + .../ConvexDecomposition/cd_vector.h | 1209 ++ .../ConvexDecomposition/cd_wavefront.cpp | 858 + .../ConvexDecomposition/cd_wavefront.h | 82 + .../ConvexDecomposition/concavity.cpp | 821 + .../ConvexDecomposition/concavity.h | 81 + .../ConvexDecomposition/fitsphere.cpp | 378 + .../ConvexDecomposition/fitsphere.h | 70 + .../ConvexDecomposition/float_math.cpp | 463 + .../ConvexDecomposition/float_math.h | 112 + .../ConvexDecomposition/meshvolume.cpp | 251 + .../ConvexDecomposition/meshvolume.h | 70 + .../ConvexDecomposition/planetri.cpp | 314 + .../ConvexDecomposition/planetri.h | 82 + .../ConvexDecomposition/raytri.cpp | 160 + .../ConvexDecomposition/raytri.h | 69 + .../ConvexDecomposition/splitplane.cpp | 339 + .../ConvexDecomposition/splitplane.h | 76 + .../ConvexDecomposition/triangulate.cpp | 410 + .../ConvexDecomposition/triangulate.h | 85 + .../ConvexDecomposition/vlookup.cpp | 340 + .../ConvexDecomposition/vlookup.h | 143 + .../ConvexDecomposition/DecomposeSample.cpp | 668 + .../ConvexDecomposition/DecomposeSample.exe | Bin 0 -> 151552 bytes .../ConvexDecomposition/DecomposeSample.sln | 21 + .../ConvexDecomposition/DecomposeSample.suo | Bin 0 -> 8704 bytes .../DecomposeSample.vcproj | 240 + .../ConvexDecomposition/Makefile | 93 + .../ConvexDecomposition/chair.obj | 3083 +++ .../ConvexDecomposition/readme.txt | 75 + convex_decomposition/Makefile | 33 + .../convex_decomposition.patch | 429 + convex_decomposition/manifest.xml | 14 + ivcon/CMakeLists.txt | 9 + ivcon/Makefile | 1 + ivcon/manifest.xml | 14 + ivcon/src/ivcon.c | 16707 ++++++++++++++++ kdl_parser/CMakeLists.txt | 38 + kdl_parser/Makefile | 1 + kdl_parser/include/kdl_parser/dom_parser.hpp | 54 + kdl_parser/include/kdl_parser/xml_parser.hpp | 53 + kdl_parser/manifest.xml | 23 + kdl_parser/pr2.urdf | 2542 +++ kdl_parser/src/dom_parser.cpp | 173 + kdl_parser/src/xml_parser.cpp | 365 + kdl_parser/test/example_dom.cpp | 105 + kdl_parser/test/example_xml.cpp | 99 + kdl_parser/test/pr2_desc.xml | 3541 ++++ kdl_parser/test/pr2_desc_bracket.xml | 22 + kdl_parser/test/pr2_desc_bracket2.xml | 22 + kdl_parser/test/pr2_desc_vector.xml | 22 + kdl_parser/test/test_kdl_parser.cpp | 93 + kdl_parser/test/test_kdl_parser.launch | 6 + resource_retriever/CMakeLists.txt | 35 + resource_retriever/Makefile | 1 + .../include/resource_retriever/retriever.h | 85 + resource_retriever/mainpage.dox | 14 + resource_retriever/manifest.xml | 21 + resource_retriever/src/retriever.cpp | 147 + resource_retriever/test/CMakeLists.txt | 4 + resource_retriever/test/test.cpp | 140 + resource_retriever/test/test.txt | 1 + robot_state_publisher/CMakeLists.txt | 38 + robot_state_publisher/Makefile | 1 + .../joint_state_listener.h | 69 + .../robot_state_publisher.h | 76 + .../treefksolverposfull_recursive.hpp | 48 + robot_state_publisher/manifest.xml | 27 + .../src/joint_state_listener.cpp | 86 + .../src/robot_state_publisher.cpp | 106 + robot_state_publisher/src/state_publisher.cpp | 77 + .../src/treefksolverposfull_recursive.cpp | 76 + robot_state_publisher/test/pr2.urdf | 3117 +++ robot_state_publisher/test/test_publisher.cpp | 136 + .../test/test_publisher.launch | 5 + stack.xml | 15 + urdf/CMakeLists.txt | 36 + urdf/Makefile | 1 + urdf/include/urdf/color.h | 96 + urdf/include/urdf/joint.h | 204 + urdf/include/urdf/link.h | 238 + urdf/include/urdf/model.h | 111 + urdf/include/urdf/pose.h | 232 + urdf/mainpage.dox | 209 + urdf/manifest.xml | 19 + urdf/src/joint.cpp | 387 + urdf/src/link.cpp | 434 + urdf/src/model.cpp | 409 + urdf/test/parse_test.cpp | 104 + urdf/test/pr2_desc.xml | 2542 +++ urdf/test/pr2_desc_bracket.xml | 20 + urdf/test/pr2_desc_double.xml | 39 + urdf/test/pr2_desc_double_joint.xml | 38 + urdf/test/pr2_desc_loop.xml | 39 + urdf/test/pr2_desc_no_joint.xml | 12 + urdf/test/pr2_desc_no_joint2.xml | 20 + urdf/test/pr2_desc_parent_itself.xml | 20 + urdf/test/pr2_desc_two_trees.xml | 39 + urdf/test/test_robot_model_parser.cpp | 98 + urdf/test/test_robot_model_parser.launch | 3 + 109 files changed, 50909 insertions(+) create mode 100644 CMakeLists.txt create mode 100644 Makefile create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/ConvexDecomposition.cpp create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/ConvexDecomposition.h create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/bestfit.cpp create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/bestfit.h create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/bestfitobb.cpp create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/bestfitobb.h create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/cd_hull.cpp create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/cd_hull.h create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/cd_vector.h create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/cd_wavefront.cpp create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/cd_wavefront.h create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/concavity.cpp create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/concavity.h create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/fitsphere.cpp create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/fitsphere.h create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/float_math.cpp create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/float_math.h create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/meshvolume.cpp create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/meshvolume.h create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/planetri.cpp create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/planetri.h create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/raytri.cpp create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/raytri.h create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/splitplane.cpp create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/splitplane.h create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/triangulate.cpp create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/triangulate.h create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/vlookup.cpp create mode 100644 convex_decomposition/ConvexDecomposition/ConvexDecomposition/vlookup.h create mode 100644 convex_decomposition/ConvexDecomposition/DecomposeSample.cpp create mode 100644 convex_decomposition/ConvexDecomposition/DecomposeSample.exe create mode 100644 convex_decomposition/ConvexDecomposition/DecomposeSample.sln create mode 100644 convex_decomposition/ConvexDecomposition/DecomposeSample.suo create mode 100644 convex_decomposition/ConvexDecomposition/DecomposeSample.vcproj create mode 100644 convex_decomposition/ConvexDecomposition/Makefile create mode 100644 convex_decomposition/ConvexDecomposition/chair.obj create mode 100644 convex_decomposition/ConvexDecomposition/readme.txt create mode 100644 convex_decomposition/Makefile create mode 100644 convex_decomposition/convex_decomposition.patch create mode 100644 convex_decomposition/manifest.xml create mode 100644 ivcon/CMakeLists.txt create mode 100644 ivcon/Makefile create mode 100644 ivcon/manifest.xml create mode 100644 ivcon/src/ivcon.c create mode 100644 kdl_parser/CMakeLists.txt create mode 100644 kdl_parser/Makefile create mode 100644 kdl_parser/include/kdl_parser/dom_parser.hpp create mode 100644 kdl_parser/include/kdl_parser/xml_parser.hpp create mode 100644 kdl_parser/manifest.xml create mode 100644 kdl_parser/pr2.urdf create mode 100644 kdl_parser/src/dom_parser.cpp create mode 100644 kdl_parser/src/xml_parser.cpp create mode 100644 kdl_parser/test/example_dom.cpp create mode 100644 kdl_parser/test/example_xml.cpp create mode 100644 kdl_parser/test/pr2_desc.xml create mode 100644 kdl_parser/test/pr2_desc_bracket.xml create mode 100644 kdl_parser/test/pr2_desc_bracket2.xml create mode 100644 kdl_parser/test/pr2_desc_vector.xml create mode 100644 kdl_parser/test/test_kdl_parser.cpp create mode 100644 kdl_parser/test/test_kdl_parser.launch create mode 100644 resource_retriever/CMakeLists.txt create mode 100644 resource_retriever/Makefile create mode 100644 resource_retriever/include/resource_retriever/retriever.h create mode 100644 resource_retriever/mainpage.dox create mode 100644 resource_retriever/manifest.xml create mode 100644 resource_retriever/src/retriever.cpp create mode 100644 resource_retriever/test/CMakeLists.txt create mode 100644 resource_retriever/test/test.cpp create mode 100644 resource_retriever/test/test.txt create mode 100644 robot_state_publisher/CMakeLists.txt create mode 100644 robot_state_publisher/Makefile create mode 100644 robot_state_publisher/include/robot_state_publisher/joint_state_listener.h create mode 100644 robot_state_publisher/include/robot_state_publisher/robot_state_publisher.h create mode 100644 robot_state_publisher/include/robot_state_publisher/treefksolverposfull_recursive.hpp create mode 100644 robot_state_publisher/manifest.xml create mode 100644 robot_state_publisher/src/joint_state_listener.cpp create mode 100644 robot_state_publisher/src/robot_state_publisher.cpp create mode 100644 robot_state_publisher/src/state_publisher.cpp create mode 100644 robot_state_publisher/src/treefksolverposfull_recursive.cpp create mode 100644 robot_state_publisher/test/pr2.urdf create mode 100644 robot_state_publisher/test/test_publisher.cpp create mode 100644 robot_state_publisher/test/test_publisher.launch create mode 100644 stack.xml create mode 100644 urdf/CMakeLists.txt create mode 100644 urdf/Makefile create mode 100644 urdf/include/urdf/color.h create mode 100644 urdf/include/urdf/joint.h create mode 100644 urdf/include/urdf/link.h create mode 100644 urdf/include/urdf/model.h create mode 100644 urdf/include/urdf/pose.h create mode 100644 urdf/mainpage.dox create mode 100644 urdf/manifest.xml create mode 100644 urdf/src/joint.cpp create mode 100644 urdf/src/link.cpp create mode 100644 urdf/src/model.cpp create mode 100644 urdf/test/parse_test.cpp create mode 100644 urdf/test/pr2_desc.xml create mode 100644 urdf/test/pr2_desc_bracket.xml create mode 100644 urdf/test/pr2_desc_double.xml create mode 100644 urdf/test/pr2_desc_double_joint.xml create mode 100644 urdf/test/pr2_desc_loop.xml create mode 100644 urdf/test/pr2_desc_no_joint.xml create mode 100644 urdf/test/pr2_desc_no_joint2.xml create mode 100644 urdf/test/pr2_desc_parent_itself.xml create mode 100644 urdf/test/pr2_desc_two_trees.xml create mode 100644 urdf/test/test_robot_model_parser.cpp create mode 100644 urdf/test/test_robot_model_parser.launch diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..84534d8 --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,19 @@ +cmake_minimum_required(VERSION 2.4.6) +include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) + +set(ROSPACK_MAKEDIST true) + +# Append to CPACK_SOURCE_IGNORE_FILES a semicolon-separated list of +# directories (or patterns, but directories should suffice) that should +# be excluded from the distro. This is not the place to put things that +# should be ignored everywhere, like "build" directories; that happens in +# rosbuild/rosbuild.cmake. Here should be listed packages that aren't +# ready for inclusion in a distro. +# +# This list is combined with the list in rosbuild/rosbuild.cmake. Note +# that CMake 2.6 may be required to ensure that the two lists are combined +# properly. CMake 2.4 seems to have unpredictable scoping rules for such +# variables. +#list(APPEND CPACK_SOURCE_IGNORE_FILES /core/experimental) + +rosbuild_make_distribution(0.1.0) diff --git a/Makefile b/Makefile new file mode 100644 index 0000000..a818cca --- /dev/null +++ b/Makefile @@ -0,0 +1 @@ +include $(shell rospack find mk)/cmake_stack.mk \ No newline at end of file diff --git a/convex_decomposition/ConvexDecomposition/ConvexDecomposition/ConvexDecomposition.cpp b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/ConvexDecomposition.cpp new file mode 100644 index 0000000..4198082 --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/ConvexDecomposition.cpp @@ -0,0 +1,1065 @@ +#include +#include +#include +#include + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + + +#include +#include + +#include "ConvexDecomposition.h" +#include "cd_vector.h" +#include "cd_hull.h" +#include "bestfit.h" +#include "planetri.h" +#include "vlookup.h" +#include "splitplane.h" +#include "meshvolume.h" +#include "concavity.h" +#include "bestfitobb.h" +#include "fitsphere.h" +#include "triangulate.h" +#include "float_math.h" + +#define MAKE_MESH 1 +#define CLOSE_FACE 0 + +static unsigned int MAXDEPTH=8; +static double CONCAVE_PERCENT=1.0f; +static double MERGE_PERCENT=2.0f; + + +using namespace ConvexDecomposition; + +typedef std::vector< unsigned int > UintVector; + +namespace ConvexDecomposition +{ + +class Edge +{ +public: + + Edge(unsigned int i1,unsigned int i2) + { + mE1 = i1; + mE2 = i2; + mUsed = false; + } + + unsigned int mE1; + unsigned int mE2; + bool mUsed; +}; + +typedef std::vector< Edge > EdgeVector; + +class FaceTri +{ +public: + FaceTri(void) { }; + + FaceTri(const double *vertices,unsigned int i1,unsigned int i2,unsigned int i3) + { + mP1.Set( &vertices[i1*3] ); + mP2.Set( &vertices[i2*3] ); + mP3.Set( &vertices[i3*3] ); + } + + Vector3d mP1; + Vector3d mP2; + Vector3d mP3; + Vector3d mNormal; + +}; + + + +class CHull +{ +public: + CHull(const ConvexResult &result) + { + mResult = new ConvexResult(result); + mVolume = computeMeshVolume( result.mHullVertices, result.mHullTcount, result.mHullIndices ); + + mDiagonal = getBoundingRegion( result.mHullVcount, result.mHullVertices, sizeof(double)*3, mMin, mMax ); + + double dx = mMax[0] - mMin[0]; + double dy = mMax[1] - mMin[1]; + double dz = mMax[2] - mMin[2]; + + dx*=0.1f; // inflate 1/10th on each edge + dy*=0.1f; // inflate 1/10th on each edge + dz*=0.1f; // inflate 1/10th on each edge + + mMin[0]-=dx; + mMin[1]-=dy; + mMin[2]-=dz; + + mMax[0]+=dx; + mMax[1]+=dy; + mMax[2]+=dz; + + + } + + ~CHull(void) + { + delete mResult; + } + + bool overlap(const CHull &h) const + { + return overlapAABB(mMin,mMax, h.mMin, h.mMax ); + } + + double mMin[3]; + double mMax[3]; + double mVolume; + double mDiagonal; // long edge.. + ConvexResult *mResult; +}; + +// Usage: std::sort( list.begin(), list.end(), StringSortRef() ); +class CHullSort +{ + public: + + bool operator()(const CHull *a,const CHull *b) const + { + return a->mVolume < b->mVolume; + } +}; + + +typedef std::vector< CHull * > CHullVector; + + +class ConvexBuilder : public ConvexDecompInterface +{ +public: + ConvexBuilder(ConvexDecompInterface *callback) + { + mCallback = callback; + }; + + ~ConvexBuilder(void) + { + CHullVector::iterator i; + for (i=mChulls.begin(); i!=mChulls.end(); ++i) + { + CHull *cr = (*i); + delete cr; + } + } + + bool isDuplicate(unsigned int i1,unsigned int i2,unsigned int i3, + unsigned int ci1,unsigned int ci2,unsigned int ci3) + { + unsigned int dcount = 0; + + assert( i1 != i2 && i1 != i3 && i2 != i3 ); + assert( ci1 != ci2 && ci1 != ci3 && ci2 != ci3 ); + + if ( i1 == ci1 || i1 == ci2 || i1 == ci3 ) dcount++; + if ( i2 == ci1 || i2 == ci2 || i2 == ci3 ) dcount++; + if ( i3 == ci1 || i3 == ci2 || i3 == ci3 ) dcount++; + + return dcount == 3; + } + + void getMesh(const ConvexResult &cr,VertexLookup vc) + { + unsigned int *src = cr.mHullIndices; + + for (unsigned int i=0; ioverlap(*b) ) return 0; // if their AABB's (with a little slop) don't overlap, then return. + + if ( MERGE_PERCENT < 0 ) return 0; + + assert( a->mVolume > 0 ); + assert( b->mVolume > 0 ); + + CHull *ret = 0; + + // ok..we are going to combine both meshes into a single mesh + // and then we are going to compute the concavity... + + VertexLookup vc = Vl_createVertexLookup(); + + getMesh( *a->mResult, vc); + getMesh( *b->mResult, vc); + + unsigned int vcount = Vl_getVcount(vc); + const double *vertices = Vl_getVertices(vc); + + HullResult hresult; + HullLibrary hl; + HullDesc desc; + + desc.SetHullFlag(QF_TRIANGLES); + + desc.mVcount = vcount; + desc.mVertices = vertices; + desc.mVertexStride = sizeof(double)*3; + + HullError hret = hl.CreateConvexHull(desc,hresult); + + if ( hret == QE_OK ) + { + + double combineVolume = computeMeshVolume( hresult.mOutputVertices, hresult.mNumFaces, hresult.mIndices ); + double sumVolume = a->mVolume + b->mVolume; + + double percent = (sumVolume*100) / combineVolume; + + if ( percent >= (100.0f-MERGE_PERCENT) ) + { + ConvexResult cr(hresult.mNumOutputVertices, hresult.mOutputVertices, hresult.mNumFaces, hresult.mIndices); + ret = new CHull(cr); + } + } + + + Vl_releaseVertexLookup(vc); + + return ret; + } + + bool combineHulls(void) + { + + bool combine = false; + + sortChulls(mChulls); // sort the convex hulls, largest volume to least... + + CHullVector output; // the output hulls... + + + CHullVector::iterator i; + + for (i=mChulls.begin(); i!=mChulls.end() && !combine; ++i) + { + CHull *cr = (*i); + + CHullVector::iterator j; + for (j=mChulls.begin(); j!=mChulls.end(); ++j) + { + CHull *match = (*j); + + if ( cr != match ) // don't try to merge a hull with itself, that be stoopid + { + + CHull *merge = canMerge(cr,match); // if we can merge these two.... + + if ( merge ) + { + + output.push_back(merge); + + + ++i; + while ( i != mChulls.end() ) + { + CHull *cr = (*i); + if ( cr != match ) + { + output.push_back(cr); + } + i++; + } + + delete cr; + delete match; + combine = true; + break; + } + } + } + + if ( combine ) + { + break; + } + else + { + output.push_back(cr); + } + + } + + if ( combine ) + { + mChulls.clear(); + mChulls = output; + output.clear(); + } + + + return combine; + } + + unsigned int process(const DecompDesc &desc) + { + + unsigned int ret = 0; + + MAXDEPTH = desc.mDepth; + CONCAVE_PERCENT = desc.mCpercent; + MERGE_PERCENT = desc.mPpercent; + + + doConvexDecomposition(desc.mVcount, desc.mVertices, desc.mTcount, desc.mIndices,this,0,0); + + + while ( combineHulls() ); // keep combinging hulls until I can't combine any more... + + CHullVector::iterator i; + for (i=mChulls.begin(); i!=mChulls.end(); ++i) + { + CHull *cr = (*i); + + // before we hand it back to the application, we need to regenerate the hull based on the + // limits given by the user. + + const ConvexResult &c = *cr->mResult; // the high resolution hull... + + HullResult result; + HullLibrary hl; + HullDesc hdesc; + + hdesc.SetHullFlag(QF_TRIANGLES); + + hdesc.mVcount = c.mHullVcount; + hdesc.mVertices = c.mHullVertices; + hdesc.mVertexStride = sizeof(double)*3; + hdesc.mMaxVertices = desc.mMaxVertices; // maximum number of vertices allowed in the output + + if ( desc.mSkinWidth > 0 ) + { + hdesc.mSkinWidth = desc.mSkinWidth; + hdesc.SetHullFlag(QF_SKIN_WIDTH); // do skin width computation. + } + + HullError ret = hl.CreateConvexHull(hdesc,result); + + if ( ret == QE_OK ) + { + ConvexResult r(result.mNumOutputVertices, result.mOutputVertices, result.mNumFaces, result.mIndices); + + r.mHullVolume = computeMeshVolume( result.mOutputVertices, result.mNumFaces, result.mIndices ); // the volume of the hull. + + mCallback->ConvexDecompResult(r); + } + + + delete cr; + } + + ret = mChulls.size(); + + mChulls.clear(); + + return ret; + } + + + virtual void ConvexDebugTri(const double *p1,const double *p2,const double *p3,unsigned int color) + { + mCallback->ConvexDebugTri(p1,p2,p3,color); + } + + virtual void ConvexDebugOBB(const double *sides, const double *matrix,unsigned int color) + { + mCallback->ConvexDebugOBB(sides,matrix,color); + } + virtual void ConvexDebugPoint(const double *p,double dist,unsigned int color) + { + mCallback->ConvexDebugPoint(p,dist,color); + } + + virtual void ConvexDebugBound(const double *bmin,const double *bmax,unsigned int color) + { + mCallback->ConvexDebugBound(bmin,bmax,color); + } + + virtual void ConvexDecompResult(ConvexResult &result) + { + CHull *ch = new CHull(result); + mChulls.push_back(ch); + } + + void sortChulls(CHullVector &hulls) + { + std::sort( hulls.begin(), hulls.end(), CHullSort() ); + } + +#define EPSILON 0.001f + + bool isEdge(const Vector3d &p,const double *plane) + { + bool ret = false; + + double dist = fabs(fm_distToPlane(plane,p.Ptr())); + + if ( dist < EPSILON ) + { + ret = true; + } + + + return ret; + } + + void addEdge(const Vector3d &p1,const Vector3d &p2,EdgeVector &edges,VertexLookup split,const double *plane) + { + if ( isEdge(p1,plane) && isEdge(p2,plane) ) + { + unsigned int i1 = Vl_getIndex(split,p1.Ptr()); + unsigned int i2 = Vl_getIndex(split,p2.Ptr()); + + bool found = false; + + for (unsigned int i=0; i &p1, + const Vector3d &p2, + const Vector3d &p3, + EdgeVector &edges, + VertexLookup split, + const double *plane) + { + bool ret = false; + + unsigned int i1 = Vl_getIndex(vl, p1.Ptr() ); + unsigned int i2 = Vl_getIndex(vl, p2.Ptr() ); + unsigned int i3 = Vl_getIndex(vl, p3.Ptr() ); + + // do *not* process degenerate triangles! + + if ( i1 != i2 && i1 != i3 && i2 != i3 ) + { + + list.push_back(i1); + list.push_back(i2); + list.push_back(i3); +#if CLOSE_FACE + addEdge(p1,p2,edges,split,plane); + addEdge(p2,p3,edges,split,plane); + addEdge(p3,p1,edges,split,plane); +#endif + ret = true; + } + return ret; + } + + void saveEdges(VertexLookup vl,const EdgeVector &edges,bool front) + { + char scratch[512]; + if ( front ) + { + static int fcount=1; + sprintf(scratch,"CD_Front%d.obj", fcount++); + } + else + { + static int bcount=1; + sprintf(scratch,"CD_Back%d.obj", bcount++); + } + + FILE *fph = fopen(scratch,"wb"); + if (fph) + { + unsigned int vcount = Vl_getVcount(vl); + const double *vertices = Vl_getVertices(vl); + fprintf(fph,"v 10 10 0\r\n"); + for (unsigned int i=0; i= 0 ) + { + double volume; + + double c = computeConcavity( vcount, vertices, tcount, indices, callback, plane, volume ); + + if ( depth == 0 ) + { + masterVolume = volume; + } + + double percent = (c*100.0f)/masterVolume; + + if ( percent > CONCAVE_PERCENT ) // if great than 5% of the total volume is concave, go ahead and keep splitting. + { + split = true; + } + } + else + { + split = computeSplitPlane(vcount,vertices,tcount,indices,callback,plane); + } + + } + + if ( depth >= MAXDEPTH || !split ) + { + + HullResult result; + HullLibrary hl; + HullDesc desc; + + desc.SetHullFlag(QF_TRIANGLES); + + desc.mVcount = vcount; + desc.mVertices = vertices; + desc.mVertexStride = sizeof(double)*3; + + HullError ret = hl.CreateConvexHull(desc,result); + + if ( ret == QE_OK ) + { + + ConvexResult r(result.mNumOutputVertices, result.mOutputVertices, result.mNumFaces, result.mIndices); + + + callback->ConvexDecompResult(r); + } + + + return; + } + + UintVector ifront; + UintVector iback; + + EdgeVector frontEdges; + EdgeVector backEdges; + + VertexLookup vfront = Vl_createVertexLookup(); + VertexLookup vback = Vl_createVertexLookup(); + + VertexLookup splitFront = Vl_createVertexLookup(); + VertexLookup splitBack = Vl_createVertexLookup(); + + + + if ( 1 ) + { + + // ok..now we are going to 'split' all of the input triangles against this plane! + + const unsigned int *source = indices; + + for (unsigned int i=0; i front[4]; + Vector3d back[4]; + + unsigned int fcount=0; + unsigned int bcount=0; + + PlaneTriResult result; + + result = planeTriIntersection(plane,t.mP1.Ptr(),sizeof(Vector3d),0.00001f,front[0].Ptr(),fcount,back[0].Ptr(),bcount ); + + if( fcount > 4 || bcount > 4 ) + { + result = planeTriIntersection(plane,t.mP1.Ptr(),sizeof(Vector3d),0.00001f,front[0].Ptr(),fcount,back[0].Ptr(),bcount ); + } + + switch ( result ) + { + case PTR_FRONT: + + assert( fcount == 3 ); + + #if MAKE_MESH + addTri( vfront, ifront, front[0], front[1], front[2], frontEdges, splitFront, plane ); + #endif + + break; + case PTR_BACK: + assert( bcount == 3 ); + + #if MAKE_MESH + addTri( vback, iback, back[0], back[1], back[2], backEdges, splitBack, plane ); + #endif + + break; + case PTR_SPLIT: + + assert( fcount >= 3 && fcount <= 4); + assert( bcount >= 3 && bcount <= 4); + + #if MAKE_MESH + addTri( vfront, ifront, front[0], front[1], front[2], frontEdges, splitFront, plane ); + addTri( vback, iback, back[0], back[1], back[2], backEdges, splitBack, plane ); + + if ( fcount == 4 ) + { + addTri( vfront, ifront, front[0], front[2], front[3], frontEdges, splitFront, plane ); + } + + if ( bcount == 4 ) + { + addTri( vback, iback, back[0], back[2], back[3], backEdges, splitBack, plane ); + } + #endif + + break; + } + } + + +// saveEdges(vfront,frontEdges,true); +// saveEdges(vback,backEdges,false); + + // Triangulate the front surface... + if ( frontEdges.size() ) // extract polygons for the front + { + UintVector polygon; + + bool ok = extractPolygon(frontEdges,polygon,splitFront); + + while ( ok ) + { + + const double *vertices = Vl_getVertices(splitFront); + unsigned int pcount = polygon.size(); + unsigned int maxTri = pcount*3; + double *tris = new double[maxTri*9]; + + unsigned int tcount = triangulate3d(pcount,(const unsigned int *) &polygon[0], vertices, tris, maxTri, plane ); + + if ( tcount ) + { + // cool! now add these triangles to the frong.. + const double *source = tris; + for (unsigned int i=0; i= 0 ) + { + Edge &e = edges[root]; + polygon.push_back(e.mE1); + int link; + + do + { + link = findEdge(edges,e.mE2); + if ( link < 0 ) + link = findNearestEdge(edges,e.mE2,split); + + if ( link >= 0 ) + { + e = edges[link]; + polygon.push_back(e.mE1 ); + } + } while ( link >= 0 ); + + + if ( polygon.size() >= 3 ) + { + ret = true; + } + + } + + return ret; + } + +CHullVector mChulls; +ConvexDecompInterface *mCallback; + +}; + +unsigned int performConvexDecomposition(const DecompDesc &desc) +{ + unsigned int ret = 0; + + if ( desc.mCallback ) + { + ConvexBuilder cb(desc.mCallback); + + ret = cb.process(desc); + } + + return ret; +} + + + +}; diff --git a/convex_decomposition/ConvexDecomposition/ConvexDecomposition/ConvexDecomposition.h b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/ConvexDecomposition.h new file mode 100644 index 0000000..b590e2d --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/ConvexDecomposition.h @@ -0,0 +1,249 @@ +#ifndef CONVEX_DECOMPOSITION_H + +#define CONVEX_DECOMPOSITION_H + +namespace ConvexDecomposition +{ + + /*! + ** + ** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net + ** + ** Portions of this source has been released with the PhysXViewer application, as well as + ** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. + ** + ** If you find this code useful or you are feeling particularily generous I would + ** ask that you please go to http://www.amillionpixels.us and make a donation + ** to Troy DeMolay. + ** + ** DeMolay is a youth group for young men between the ages of 12 and 21. + ** It teaches strong moral principles, as well as leadership skills and + ** public speaking. The donations page uses the 'pay for pixels' paradigm + ** where, in this case, a pixel is only a single penny. Donations can be + ** made for as small as $4 or as high as a $100 block. Each person who donates + ** will get a link to their own site as well as acknowledgement on the + ** donations blog located here http://www.amillionpixels.blogspot.com/ + ** + ** If you wish to contact me you can use the following methods: + ** + ** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) + ** Skype ID: jratcliff63367 + ** Yahoo: jratcliff63367 + ** AOL: jratcliff1961 + ** email: jratcliff@infiniplex.net + ** Personal website: http://jratcliffscarab.blogspot.com + ** Coding Website: http://codesuppository.blogspot.com + ** FundRaising Blog: http://amillionpixels.blogspot.com + ** Fundraising site: http://www.amillionpixels.us + ** New Temple Site: http://newtemple.blogspot.com + ** + ** + ** The MIT license: + ** + ** Permission is hereby granted, free of charge, to any person obtaining a copy + ** of this software and associated documentation files (the "Software"), to deal + ** in the Software without restriction, including without limitation the rights + ** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + ** copies of the Software, and to permit persons to whom the Software is furnished + ** to do so, subject to the following conditions: + ** + ** The above copyright notice and this permission notice shall be included in all + ** copies or substantial portions of the Software. + + ** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + ** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + ** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + ** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, + ** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + ** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + + */ + + + +class ConvexResult +{ +public: + ConvexResult(void) + { + mHullVcount = 0; + mHullVertices = 0; + mHullTcount = 0; + mHullIndices = 0; + } + + ConvexResult(unsigned int hvcount,const double *hvertices,unsigned int htcount,const unsigned int *hindices) + { + mHullVcount = hvcount; + if ( mHullVcount ) + { + mHullVertices = new double[mHullVcount*sizeof(double)*3]; + memcpy(mHullVertices, hvertices, sizeof(double)*3*mHullVcount ); + } + else + { + mHullVertices = 0; + } + + mHullTcount = htcount; + + if ( mHullTcount ) + { + mHullIndices = new unsigned int[sizeof(unsigned int)*mHullTcount*3]; + memcpy(mHullIndices,hindices, sizeof(unsigned int)*mHullTcount*3 ); + } + else + { + mHullIndices = 0; + } + + } + + ConvexResult(const ConvexResult &r) // copy constructor, perform a deep copy of the data. + { + mHullVcount = r.mHullVcount; + if ( mHullVcount ) + { + mHullVertices = new double[mHullVcount*sizeof(double)*3]; + memcpy(mHullVertices, r.mHullVertices, sizeof(double)*3*mHullVcount ); + } + else + { + mHullVertices = 0; + } + mHullTcount = r.mHullTcount; + if ( mHullTcount ) + { + mHullIndices = new unsigned int[sizeof(unsigned int)*mHullTcount*3]; + memcpy(mHullIndices, r.mHullIndices, sizeof(unsigned int)*mHullTcount*3 ); + } + else + { + mHullIndices = 0; + } + } + + ~ConvexResult(void) + { + delete mHullVertices; + delete mHullIndices; + } + +// the convex hull. + unsigned int mHullVcount; + double * mHullVertices; + unsigned int mHullTcount; + unsigned int *mHullIndices; + + double mHullVolume; // the volume of the convex hull. + +}; + +// convert from doubles back down to floats. +class FConvexResult +{ +public: + FConvexResult(const ConvexResult &r) + { + mHullVcount = r.mHullVcount; + mHullVertices = 0; + if ( mHullVcount ) + { + mHullVertices = new float[mHullVcount*3]; + + const double *src = r.mHullVertices; + float * dest = mHullVertices; + for (unsigned int i=0; i +#include +#include +#include +#include + +// Geometric Tools, Inc. +// http://www.geometrictools.com +// Copyright (c) 1998-2006. All Rights Reserved +// +// The Wild Magic Library (WM3) source code is supplied under the terms of +// the license agreement +// http://www.geometrictools.com/License/WildMagic3License.pdf +// and may not be copied or disclosed except in accordance with the terms +// of that agreement. + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + + +#include "bestfit.h" + +namespace ConvexDecomposition +{ + +class Vec3 +{ +public: + Vec3(void) { }; + Vec3(double _x,double _y,double _z) { x = _x; y = _y; z = _z; }; + + + double dot(const Vec3 &v) + { + return x*v.x + y*v.y + z*v.z; // the dot product + } + + double x; + double y; + double z; +}; + + +class Eigen +{ +public: + + + void DecrSortEigenStuff(void) + { + Tridiagonal(); //diagonalize the matrix. + QLAlgorithm(); // + DecreasingSort(); + GuaranteeRotation(); + } + + void Tridiagonal(void) + { + double fM00 = mElement[0][0]; + double fM01 = mElement[0][1]; + double fM02 = mElement[0][2]; + double fM11 = mElement[1][1]; + double fM12 = mElement[1][2]; + double fM22 = mElement[2][2]; + + m_afDiag[0] = fM00; + m_afSubd[2] = 0; + if (fM02 != (double)0.0) + { + double fLength = sqrt(fM01*fM01+fM02*fM02); + double fInvLength = ((double)1.0)/fLength; + fM01 *= fInvLength; + fM02 *= fInvLength; + double fQ = ((double)2.0)*fM01*fM12+fM02*(fM22-fM11); + m_afDiag[1] = fM11+fM02*fQ; + m_afDiag[2] = fM22-fM02*fQ; + m_afSubd[0] = fLength; + m_afSubd[1] = fM12-fM01*fQ; + mElement[0][0] = (double)1.0; + mElement[0][1] = (double)0.0; + mElement[0][2] = (double)0.0; + mElement[1][0] = (double)0.0; + mElement[1][1] = fM01; + mElement[1][2] = fM02; + mElement[2][0] = (double)0.0; + mElement[2][1] = fM02; + mElement[2][2] = -fM01; + m_bIsRotation = false; + } + else + { + m_afDiag[1] = fM11; + m_afDiag[2] = fM22; + m_afSubd[0] = fM01; + m_afSubd[1] = fM12; + mElement[0][0] = (double)1.0; + mElement[0][1] = (double)0.0; + mElement[0][2] = (double)0.0; + mElement[1][0] = (double)0.0; + mElement[1][1] = (double)1.0; + mElement[1][2] = (double)0.0; + mElement[2][0] = (double)0.0; + mElement[2][1] = (double)0.0; + mElement[2][2] = (double)1.0; + m_bIsRotation = true; + } + } + + bool QLAlgorithm(void) + { + const int iMaxIter = 32; + + for (int i0 = 0; i0 <3; i0++) + { + int i1; + for (i1 = 0; i1 < iMaxIter; i1++) + { + int i2; + for (i2 = i0; i2 <= (3-2); i2++) + { + double fTmp = fabs(m_afDiag[i2]) + fabs(m_afDiag[i2+1]); + if ( fabs(m_afSubd[i2]) + fTmp == fTmp ) + break; + } + if (i2 == i0) + { + break; + } + + double fG = (m_afDiag[i0+1] - m_afDiag[i0])/(((double)2.0) * m_afSubd[i0]); + double fR = sqrt(fG*fG+(double)1.0); + if (fG < (double)0.0) + { + fG = m_afDiag[i2]-m_afDiag[i0]+m_afSubd[i0]/(fG-fR); + } + else + { + fG = m_afDiag[i2]-m_afDiag[i0]+m_afSubd[i0]/(fG+fR); + } + double fSin = (double)1.0, fCos = (double)1.0, fP = (double)0.0; + for (int i3 = i2-1; i3 >= i0; i3--) + { + double fF = fSin*m_afSubd[i3]; + double fB = fCos*m_afSubd[i3]; + if (fabs(fF) >= fabs(fG)) + { + fCos = fG/fF; + fR = sqrt(fCos*fCos+(double)1.0); + m_afSubd[i3+1] = fF*fR; + fSin = ((double)1.0)/fR; + fCos *= fSin; + } + else + { + fSin = fF/fG; + fR = sqrt(fSin*fSin+(double)1.0); + m_afSubd[i3+1] = fG*fR; + fCos = ((double)1.0)/fR; + fSin *= fCos; + } + fG = m_afDiag[i3+1]-fP; + fR = (m_afDiag[i3]-fG)*fSin+((double)2.0)*fB*fCos; + fP = fSin*fR; + m_afDiag[i3+1] = fG+fP; + fG = fCos*fR-fB; + for (int i4 = 0; i4 < 3; i4++) + { + fF = mElement[i4][i3+1]; + mElement[i4][i3+1] = fSin*mElement[i4][i3]+fCos*fF; + mElement[i4][i3] = fCos*mElement[i4][i3]-fSin*fF; + } + } + m_afDiag[i0] -= fP; + m_afSubd[i0] = fG; + m_afSubd[i2] = (double)0.0; + } + if (i1 == iMaxIter) + { + return false; + } + } + return true; + } + + void DecreasingSort(void) + { + //sort eigenvalues in decreasing order, e[0] >= ... >= e[iSize-1] + for (int i0 = 0, i1; i0 <= 3-2; i0++) + { + // locate maximum eigenvalue + i1 = i0; + double fMax = m_afDiag[i1]; + int i2; + for (i2 = i0+1; i2 < 3; i2++) + { + if (m_afDiag[i2] > fMax) + { + i1 = i2; + fMax = m_afDiag[i1]; + } + } + + if (i1 != i0) + { + // swap eigenvalues + m_afDiag[i1] = m_afDiag[i0]; + m_afDiag[i0] = fMax; + // swap eigenvectors + for (i2 = 0; i2 < 3; i2++) + { + double fTmp = mElement[i2][i0]; + mElement[i2][i0] = mElement[i2][i1]; + mElement[i2][i1] = fTmp; + m_bIsRotation = !m_bIsRotation; + } + } + } + } + + + void GuaranteeRotation(void) + { + if (!m_bIsRotation) + { + // change sign on the first column + for (int iRow = 0; iRow <3; iRow++) + { + mElement[iRow][0] = -mElement[iRow][0]; + } + } + } + + double mElement[3][3]; + double m_afDiag[3]; + double m_afSubd[3]; + bool m_bIsRotation; +}; + + +bool getBestFitPlane(unsigned int vcount, + const double *points, + unsigned int vstride, + const double *weights, + unsigned int wstride, + double *plane) +{ + bool ret = false; + + Vec3 kOrigin(0,0,0); + + double wtotal = 0; + + if ( 1 ) + { + const char *source = (const char *) points; + const char *wsource = (const char *) weights; + + for (unsigned int i=0; i bmax[0] ) bmax[0] = p[0]; + if ( p[1] > bmax[1] ) bmax[1] = p[1]; + if ( p[2] > bmax[2] ) bmax[2] = p[2]; + + } + + double dx = bmax[0] - bmin[0]; + double dy = bmax[1] - bmin[1]; + double dz = bmax[2] - bmin[2]; + + return sqrt( dx*dx + dy*dy + dz*dz ); + +} + + +bool overlapAABB(const double *bmin1,const double *bmax1,const double *bmin2,const double *bmax2) // return true if the two AABB's overlap. +{ + if ( bmax2[0] < bmin1[0] ) return false; // if the maximum is less than our minimum on any axis + if ( bmax2[1] < bmin1[1] ) return false; + if ( bmax2[2] < bmin1[2] ) return false; + + if ( bmin2[0] > bmax1[0] ) return false; // if the minimum is greater than our maximum on any axis + if ( bmin2[1] > bmax1[1] ) return false; // if the minimum is greater than our maximum on any axis + if ( bmin2[2] > bmax1[2] ) return false; // if the minimum is greater than our maximum on any axis + + + return true; // the extents overlap +} + +}; // end of namespace diff --git a/convex_decomposition/ConvexDecomposition/ConvexDecomposition/bestfit.h b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/bestfit.h new file mode 100644 index 0000000..2cd05dc --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/bestfit.h @@ -0,0 +1,90 @@ +#ifndef BEST_FIT_H + +#define BEST_FIT_H + +// This routine was released in 'snippet' form +// by John W. Ratcliff mailto:jratcliff@infiniplex.net +// on March 22, 2006. +// +// This routine computes the 'best fit' plane equation to +// a set of input data points with an optional per vertex +// weighting component. +// +// The implementation for this was lifted directly from +// David Eberly's Magic Software implementation. + +// computes the best fit plane to a collection of data points. +// returns the plane equation as A,B,C,D format. (Ax+By+Cz+D) + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + +namespace ConvexDecomposition +{ + + +bool getBestFitPlane(unsigned int vcount, // number of input data points + const double *points, // starting address of points array. + unsigned int vstride, // stride between input points. + const double *weights, // *optional point weighting values. + unsigned int wstride, // weight stride for each vertex. + double *plane); + + +double getBoundingRegion(unsigned int vcount,const double *points,unsigned int pstride,double *bmin,double *bmax); // returns the diagonal distance +bool overlapAABB(const double *bmin1,const double *bmax1,const double *bmin2,const double *bmax2); // return true if the two AABB's overlap. + +}; + +#endif diff --git a/convex_decomposition/ConvexDecomposition/ConvexDecomposition/bestfitobb.cpp b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/bestfitobb.cpp new file mode 100644 index 0000000..d84dd6d --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/bestfitobb.cpp @@ -0,0 +1,368 @@ +#include +#include +#include +#include +#include + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + + +// compute the 'best fit' oriented bounding box of an input point cloud by doing an exhaustive search. +// it spins the point cloud around searching for the minimal volume. It keeps narrowing down until +// it fails to find a better fit. The only dependency is on 'double_math' +// +// The inputs are: +// +// vcount : number of input vertices in the point cloud. +// points : a pointer to the first vertex. +// pstride : The stride between each point measured in bytes. +// +// The outputs are: +// +// sides : The length of the sides of the OBB as X, Y, Z distance. +// matrix : A pointer to a 4x4 matrix. This will contain the 3x3 rotation and the translation component. +// pos : The center of the OBB +// quat : The orientation of the OBB expressed as quaternion in the form of X,Y,Z,W +// +// +// Please email bug fixes or improvements to John W. Ratcliff at mailto:jratcliff@infiniplex.net +// +// If you find this source code useful donate a couple of bucks to my kid's fund raising website at +// www.amillionpixels.us +// +// More snippets at: www.codesuppository.com +// + + +#include "bestfitobb.h" +#include "float_math.h" + +namespace ConvexDecomposition +{ + +// computes the OBB for this set of points relative to this transform matrix. +void computeOBB(unsigned int vcount,const double *points,unsigned int pstride,double *sides,double *matrix) +{ + const char *src = (const char *) points; + + double bmin[3] = { 1e9, 1e9, 1e9 }; + double bmax[3] = { -1e9, -1e9, -1e9 }; + + for (unsigned int i=0; i bmax[0] ) bmax[0] = t[0]; + if ( t[1] > bmax[1] ) bmax[1] = t[1]; + if ( t[2] > bmax[2] ) bmax[2] = t[2]; + + src+=pstride; + } + + double center[3]; + + sides[0] = bmax[0]-bmin[0]; + sides[1] = bmax[1]-bmin[1]; + sides[2] = bmax[2]-bmin[2]; + + center[0] = sides[0]*0.5f+bmin[0]; + center[1] = sides[1]*0.5f+bmin[1]; + center[2] = sides[2]*0.5f+bmin[2]; + + double ocenter[3]; + + fm_rotate(matrix,center,ocenter); + + matrix[12]+=ocenter[0]; + matrix[13]+=ocenter[1]; + matrix[14]+=ocenter[2]; + +} + +void computeBestFitOBB(unsigned int vcount,const double *points,unsigned int pstride,double *sides,double *matrix) +{ + + double bmin[3]; + double bmax[3]; + + fm_getAABB(vcount,points,pstride,bmin,bmax); + + double center[3]; + + center[0] = (bmax[0]-bmin[0])*0.5f + bmin[0]; + center[1] = (bmax[1]-bmin[1])*0.5f + bmin[1]; + center[2] = (bmax[2]-bmin[2])*0.5f + bmin[2]; + + double ax = 0; + double ay = 0; + double az = 0; + + double sweep = 45.0f; // 180 degree sweep on all three axes. + double steps = 7.0f; // 7 steps on each axis) + + double bestVolume = 1e9; + double angle[3]; + + while ( sweep >= 1 ) + { + + bool found = false; + + double stepsize = sweep / steps; + + for (double x=ax-sweep; x<=ax+sweep; x+=stepsize) + { + for (double y=ay-sweep; y<=ay+sweep; y+=stepsize) + { + for (double z=az-sweep; z<=az+sweep; z+=stepsize) + { + double pmatrix[16]; + + fm_eulerMatrix( x*FM_DEG_TO_RAD, y*FM_DEG_TO_RAD, z*FM_DEG_TO_RAD, pmatrix ); + + pmatrix[3*4+0] = center[0]; + pmatrix[3*4+1] = center[1]; + pmatrix[3*4+2] = center[2]; + + double psides[3]; + + computeOBB( vcount, points, pstride, psides, pmatrix ); + + double volume = psides[0]*psides[1]*psides[2]; // the volume of the cube + + if ( volume < bestVolume ) + { + bestVolume = volume; + + sides[0] = psides[0]; + sides[1] = psides[1]; + sides[2] = psides[2]; + + angle[0] = ax; + angle[1] = ay; + angle[2] = az; + + memcpy(matrix,pmatrix,sizeof(double)*16); + found = true; // yes, we found an improvement. + } + } + } + } + + if ( found ) + { + + ax = angle[0]; + ay = angle[1]; + az = angle[2]; + + sweep*=0.5f; // sweep 1/2 the distance as the last time. + } + else + { + break; // no improvement, so just + } + + } + +} + + +void computeBestFitOBB(unsigned int vcount,const double *points,unsigned int pstride,double *sides,double *pos,double *quat) +{ + double matrix[16]; + + computeBestFitOBB(vcount,points,pstride,sides,matrix); + fm_getTranslation(matrix,pos); + fm_matrixToQuat(matrix,quat); + +} + + +void computeBestFitABB(unsigned int vcount,const double *points,unsigned int pstride,double *sides,double *pos) +{ + double bmin[3]; + double bmax[3]; + + bmin[0] = points[0]; + bmin[1] = points[1]; + bmin[2] = points[2]; + + bmax[0] = points[0]; + bmax[1] = points[1]; + bmax[2] = points[2]; + + const char *cp = (const char *) points; + for (unsigned int i=0; i bmax[0] ) bmax[0] = p[0]; + if ( p[1] > bmax[1] ) bmax[1] = p[1]; + if ( p[2] > bmax[2] ) bmax[2] = p[2]; + + cp+=pstride; + } + + + sides[0] = bmax[0] - bmin[0]; + sides[1] = bmax[1] - bmin[1]; + sides[2] = bmax[2] - bmin[2]; + + pos[0] = bmin[0]+sides[0]*0.5f; + pos[1] = bmin[1]+sides[1]*0.5f; + pos[2] = bmin[2]+sides[2]*0.5f; + +} + + +void computeBestFitOBB(unsigned int vcount,const float *points,unsigned int pstride,float *sides,float *pos,float *quat) // the float version of the routine. +{ + double *temp = new double[vcount*3]; + const char *src = (const char *)points; + double *dest = temp; + for (unsigned int i=0; i bmax[0] ) bmax[0] = p[0]; + if ( p[1] > bmax[1] ) bmax[1] = p[1]; + if ( p[2] > bmax[2] ) bmax[2] = p[2]; + + cp+=pstride; + } + + + sides[0] = bmax[0] - bmin[0]; + sides[1] = bmax[1] - bmin[1]; + sides[2] = bmax[2] - bmin[2]; + + pos[0] = bmin[0]+sides[0]*0.5f; + pos[1] = bmin[1]+sides[1]*0.5f; + pos[2] = bmin[2]+sides[2]*0.5f; + +} + +}; diff --git a/convex_decomposition/ConvexDecomposition/ConvexDecomposition/bestfitobb.h b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/bestfitobb.h new file mode 100644 index 0000000..720c717 --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/bestfitobb.h @@ -0,0 +1,100 @@ +#ifndef BEST_FIT_OBB_H + +#define BEST_FIT_OBB_H + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + + +// compute the 'best fit' oriented bounding box of an input point cloud by doing an exhaustive search. +// it spins the point cloud around searching for the minimal volume. It keeps narrowing down until +// it fails to find a better fit. The only dependency is on 'double_math' +// +// The inputs are: +// +// vcount : number of input vertices in the point cloud. +// points : a pointer to the first vertex. +// pstride : The stride between each point measured in bytes. +// +// The outputs are: +// +// sides : The length of the sides of the OBB as X, Y, Z distance. +// matrix : A pointer to a 4x4 matrix. This will contain the 3x3 rotation and the translation component. +// pos : The center of the OBB +// quat : The orientation of the OBB expressed as quaternion in the form of X,Y,Z,W +// +// +// Please email bug fixes or improvements to John W. Ratcliff at mailto:jratcliff@infiniplex.net +// +// If you find this source code useful donate a couple of bucks to my kid's fund raising website at +// www.amillionpixels.us +// +// More snippets at: www.codesuppository.com +// + +namespace ConvexDecomposition +{ + +void computeBestFitOBB(unsigned int vcount,const double *points,unsigned int pstride,double *sides,double *matrix); +void computeBestFitOBB(unsigned int vcount,const double *points,unsigned int pstride,double *sides,double *pos,double *quat); +void computeBestFitABB(unsigned int vcount,const double *points,unsigned int pstride,double *sides,double *pos); + + +void computeBestFitOBB(unsigned int vcount,const float *points,unsigned int pstride,float *sides,float *pos,float *quat); // the float version of the routine. +void computeBestFitABB(unsigned int vcount,const float *points,unsigned int pstride,float *sides,float *pos); + +}; + +#endif diff --git a/convex_decomposition/ConvexDecomposition/ConvexDecomposition/cd_hull.cpp b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/cd_hull.cpp new file mode 100644 index 0000000..74cec01 --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/cd_hull.cpp @@ -0,0 +1,3650 @@ +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + +#include +#include +#include +#include +#include +#include + + +#include +#include + +#include "cd_hull.h" + +#define STANDALONE 1 // This #define is used when tranferring this source code to other projects + +#if STANDALONE + +#undef NX_ALLOC +#undef NX_FREE + +#define NX_ALLOC(x,y) malloc(x) +#define NX_FREE(x) free(x) + +#else +#include "Allocateable.h" +#endif + +namespace ConvexDecomposition +{ + +//***************************************************** +//*** DARRAY.H +//***************************************************** + +template class ArrayRet; +template class Array +{ + public: + Array(int s=0); + Array(Array &array); + Array(ArrayRet &array); + ~Array(); + void allocate(int s); + void SetSize(int s); + void Pack(); + Type& Add(Type); + void AddUnique(Type); + int Contains(Type); + void Insert(Type,int); + int IndexOf(Type); + void Remove(Type); + void DelIndex(int i); + Type * element; + int count; + int array_size; + const Type &operator[](int i) const { assert(i>=0 && i=0 && i &operator=(Array &array); + Array &operator=(ArrayRet &array); + // operator ArrayRet &() { return *(ArrayRet *)this;} // this worked but i suspect could be dangerous +}; + +template class ArrayRet:public Array +{ +}; + +template Array::Array(int s) +{ + count=0; + array_size = 0; + element = NULL; + if(s) + { + allocate(s); + } +} + + +template Array::Array(Array &array) +{ + count=0; + array_size = 0; + element = NULL; + for(int i=0;i Array::Array(ArrayRet &array) +{ + *this = array; +} +template Array &Array::operator=(ArrayRet &array) +{ + count=array.count; + array_size = array.array_size; + element = array.element; + array.element=NULL; + array.count=0; + array.array_size=0; + return *this; +} + + +template Array &Array::operator=(Array &array) +{ + count=0; + for(int i=0;i Array::~Array() +{ + if (element != NULL) + { + NX_FREE(element); + } + count=0;array_size=0;element=NULL; +} + +template void Array::allocate(int s) +{ + assert(s>0); + assert(s>=count); + Type *old = element; + array_size =s; + element = (Type *) NX_ALLOC( sizeof(Type)*array_size, CONVEX_TEMP ); + assert(element); + for(int i=0;i void Array::SetSize(int s) +{ + if(s==0) + { + if(element) + { + NX_FREE(element); + element = NULL; + } + array_size = s; + } + else + { + allocate(s); + } + count=s; +} + +template void Array::Pack() +{ + allocate(count); +} + +template Type& Array::Add(Type t) +{ + assert(count<=array_size); + if(count==array_size) + { + allocate((array_size)?array_size *2:16); + } + element[count++] = t; + return element[count-1]; +} + +template int Array::Contains(Type t) +{ + int i; + int found=0; + for(i=0;i void Array::AddUnique(Type t) +{ + if(!Contains(t)) Add(t); +} + + +template void Array::DelIndex(int i) +{ + assert(i void Array::Remove(Type t) +{ + int i; + for(i=0;i void Array::Insert(Type t,int k) +{ + int i=count; + Add(t); // to allocate space + while(i>k) + { + element[i]=element[i-1]; + i--; + } + assert(i==k); + element[k]=t; +} + + +template int Array::IndexOf(Type t) +{ + int i; + for(i=0;i Member )))- ((char*)NULL)) + + + +int argmin(double a[],int n); +double sqr(double a); +double clampf(double a) ; +double Round(double a,double precision); +double Interpolate(const double &f0,const double &f1,double alpha) ; + +template +void Swap(T &a,T &b) +{ + T tmp = a; + a=b; + b=tmp; +} + + + +template +T Max(const T &a,const T &b) +{ + return (a>b)?a:b; +} + +template +T Min(const T &a,const T &b) +{ + return (a=0&&i<2);return ((double*)this)[i];} + const double& operator[](int i) const {assert(i>=0&&i<2);return ((double*)this)[i];} +}; +inline double2 operator-( const double2& a, const double2& b ){return double2(a.x-b.x,a.y-b.y);} +inline double2 operator+( const double2& a, const double2& b ){return double2(a.x+b.x,a.y+b.y);} + +//--------- 3D --------- + +class double3 // 3D +{ + public: + double x,y,z; + double3(){x=0;y=0;z=0;}; + double3(double _x,double _y,double _z){x=_x;y=_y;z=_z;}; + //operator double *() { return &x;}; + double& operator[](int i) {assert(i>=0&&i<3);return ((double*)this)[i];} + const double& operator[](int i) const {assert(i>=0&&i<3);return ((double*)this)[i];} +# ifdef PLUGIN_3DSMAX + double3(const Point3 &p):x(p.x),y(p.y),z(p.z){} + operator Point3(){return *((Point3*)this);} +# endif +}; + + +double3& operator+=( double3 &a, const double3& b ); +double3& operator-=( double3 &a ,const double3& b ); +double3& operator*=( double3 &v ,const double s ); +double3& operator/=( double3 &v, const double s ); + +double magnitude( const double3& v ); +double3 normalize( const double3& v ); +double3 safenormalize(const double3 &v); +double3 vabs(const double3 &v); +double3 operator+( const double3& a, const double3& b ); +double3 operator-( const double3& a, const double3& b ); +double3 operator-( const double3& v ); +double3 operator*( const double3& v, const double s ); +double3 operator*( const double s, const double3& v ); +double3 operator/( const double3& v, const double s ); +inline int operator==( const double3 &a, const double3 &b ) { return (a.x==b.x && a.y==b.y && a.z==b.z); } +inline int operator!=( const double3 &a, const double3 &b ) { return (a.x!=b.x || a.y!=b.y || a.z!=b.z); } +// due to ambiguity and inconsistent standards ther are no overloaded operators for mult such as va*vb. +double dot( const double3& a, const double3& b ); +double3 cmul( const double3 &a, const double3 &b); +double3 cross( const double3& a, const double3& b ); +double3 Interpolate(const double3 &v0,const double3 &v1,double alpha); +double3 Round(const double3& a,double precision); +double3 VectorMax(const double3 &a, const double3 &b); +double3 VectorMin(const double3 &a, const double3 &b); + + + +class double3x3 +{ + public: + double3 x,y,z; // the 3 rows of the Matrix + double3x3(){} + double3x3(double xx,double xy,double xz,double yx,double yy,double yz,double zx,double zy,double zz):x(xx,xy,xz),y(yx,yy,yz),z(zx,zy,zz){} + double3x3(double3 _x,double3 _y,double3 _z):x(_x),y(_y),z(_z){} + double3& operator[](int i) {assert(i>=0&&i<3);return (&x)[i];} + const double3& operator[](int i) const {assert(i>=0&&i<3);return (&x)[i];} + double& operator()(int r, int c) {assert(r>=0&&r<3&&c>=0&&c<3);return ((&x)[r])[c];} + const double& operator()(int r, int c) const {assert(r>=0&&r<3&&c>=0&&c<3);return ((&x)[r])[c];} +}; +double3x3 Transpose( const double3x3& m ); +double3 operator*( const double3& v , const double3x3& m ); +double3 operator*( const double3x3& m , const double3& v ); +double3x3 operator*( const double3x3& m , const double& s ); +double3x3 operator*( const double3x3& ma, const double3x3& mb ); +double3x3 operator/( const double3x3& a, const double& s ) ; +double3x3 operator+( const double3x3& a, const double3x3& b ); +double3x3 operator-( const double3x3& a, const double3x3& b ); +double3x3 &operator+=( double3x3& a, const double3x3& b ); +double3x3 &operator-=( double3x3& a, const double3x3& b ); +double3x3 &operator*=( double3x3& a, const double& s ); +double Determinant(const double3x3& m ); +double3x3 Inverse(const double3x3& a); // its just 3x3 so we simply do that cofactor method + + +//-------- 4D Math -------- + +class double4 +{ +public: + double x,y,z,w; + double4(){x=0;y=0;z=0;w=0;}; + double4(double _x,double _y,double _z,double _w){x=_x;y=_y;z=_z;w=_w;} + double4(const double3 &v,double _w){x=v.x;y=v.y;z=v.z;w=_w;} + //operator double *() { return &x;}; + double& operator[](int i) {assert(i>=0&&i<4);return ((double*)this)[i];} + const double& operator[](int i) const {assert(i>=0&&i<4);return ((double*)this)[i];} + const double3& xyz() const { return *((double3*)this);} + double3& xyz() { return *((double3*)this);} +}; + + +struct D3DXMATRIX; + +class double4x4 +{ + public: + double4 x,y,z,w; // the 4 rows + double4x4(){} + double4x4(const double4 &_x, const double4 &_y, const double4 &_z, const double4 &_w):x(_x),y(_y),z(_z),w(_w){} + double4x4(double m00, double m01, double m02, double m03, + double m10, double m11, double m12, double m13, + double m20, double m21, double m22, double m23, + double m30, double m31, double m32, double m33 ) + :x(m00,m01,m02,m03),y(m10,m11,m12,m13),z(m20,m21,m22,m23),w(m30,m31,m32,m33){} + double& operator()(int r, int c) {assert(r>=0&&r<4&&c>=0&&c<4);return ((&x)[r])[c];} + const double& operator()(int r, int c) const {assert(r>=0&&r<4&&c>=0&&c<4);return ((&x)[r])[c];} + operator double* () {return &x.x;} + operator const double* () const {return &x.x;} + operator struct D3DXMATRIX* () { return (struct D3DXMATRIX*) this;} + operator const struct D3DXMATRIX* () const { return (struct D3DXMATRIX*) this;} +}; + + +int operator==( const double4 &a, const double4 &b ); +double4 Homogenize(const double3 &v3,const double &w=1.0f); // Turns a 3D double3 4D vector4 by appending w +double4 cmul( const double4 &a, const double4 &b); +double4 operator*( const double4 &v, double s); +double4 operator*( double s, const double4 &v); +double4 operator+( const double4 &a, const double4 &b); +double4 operator-( const double4 &a, const double4 &b); +double4x4 operator*( const double4x4& a, const double4x4& b ); +double4 operator*( const double4& v, const double4x4& m ); +double4x4 Inverse(const double4x4 &m); +double4x4 MatrixRigidInverse(const double4x4 &m); +double4x4 MatrixTranspose(const double4x4 &m); +double4x4 MatrixPerspectiveFov(double fovy, double Aspect, double zn, double zf ); +double4x4 MatrixTranslation(const double3 &t); +double4x4 MatrixRotationZ(const double angle_radians); +double4x4 MatrixLookAt(const double3& eye, const double3& at, const double3& up); +int operator==( const double4x4 &a, const double4x4 &b ); + + +//-------- Quaternion ------------ + +class Quaternion :public double4 +{ + public: + Quaternion() { x = y = z = 0.0f; w = 1.0f; } + Quaternion( double3 v, double t ) { v = normalize(v); w = cos(t/2.0f); v = v*sin(t/2.0f); x = v.x; y = v.y; z = v.z; } + Quaternion(double _x, double _y, double _z, double _w){x=_x;y=_y;z=_z;w=_w;} + double angle() const { return acos(w)*2.0f; } + double3 axis() const { double3 a(x,y,z); if(fabs(angle())<0.0000001f) return double3(1,0,0); return a*(1/sin(angle()/2.0f)); } + double3 xdir() const { return double3( 1-2*(y*y+z*z), 2*(x*y+w*z), 2*(x*z-w*y) ); } + double3 ydir() const { return double3( 2*(x*y-w*z),1-2*(x*x+z*z), 2*(y*z+w*x) ); } + double3 zdir() const { return double3( 2*(x*z+w*y), 2*(y*z-w*x),1-2*(x*x+y*y) ); } + double3x3 getmatrix() const { return double3x3( xdir(), ydir(), zdir() ); } + operator double3x3() { return getmatrix(); } + void Normalize(); +}; + +Quaternion& operator*=(Quaternion& a, double s ); +Quaternion operator*( const Quaternion& a, double s ); +Quaternion operator*( const Quaternion& a, const Quaternion& b); +Quaternion operator+( const Quaternion& a, const Quaternion& b ); +Quaternion normalize( Quaternion a ); +double dot( const Quaternion &a, const Quaternion &b ); +double3 operator*( const Quaternion& q, const double3& v ); +double3 operator*( const double3& v, const Quaternion& q ); +Quaternion slerp( Quaternion a, const Quaternion& b, double interp ); +Quaternion Interpolate(const Quaternion &q0,const Quaternion &q1,double alpha); +Quaternion RotationArc(double3 v0, double3 v1 ); // returns quat q where q*v0=v1 +Quaternion Inverse(const Quaternion &q); +double4x4 MatrixFromQuatVec(const Quaternion &q, const double3 &v); + + +//------ Euler Angle ----- + +Quaternion YawPitchRoll( double yaw, double pitch, double roll ); +double Yaw( const Quaternion& q ); +double Pitch( const Quaternion& q ); +double Roll( Quaternion q ); +double Yaw( const double3& v ); +double Pitch( const double3& v ); + + +//------- Plane ---------- + +class Plane +{ + public: + double3 normal; + double dist; // distance below origin - the D from plane equasion Ax+By+Cz+D=0 + Plane(const double3 &n,double d):normal(n),dist(d){} + Plane():normal(),dist(0){} + void Transform(const double3 &position, const Quaternion &orientation); +}; + +inline Plane PlaneFlip(const Plane &plane){return Plane(-plane.normal,-plane.dist);} +inline int operator==( const Plane &a, const Plane &b ) { return (a.normal==b.normal && a.dist==b.dist); } +inline int coplanar( const Plane &a, const Plane &b ) { return (a==b || a==PlaneFlip(b)); } + + +//--------- Utility Functions ------ + +double3 PlaneLineIntersection(const Plane &plane, const double3 &p0, const double3 &p1); +double3 PlaneProject(const Plane &plane, const double3 &point); +double3 LineProject(const double3 &p0, const double3 &p1, const double3 &a); // projects a onto infinite line p0p1 +double LineProjectTime(const double3 &p0, const double3 &p1, const double3 &a); +double3 ThreePlaneIntersection(const Plane &p0,const Plane &p1, const Plane &p2); +int PolyHit(const double3 *vert,const int n,const double3 &v0, const double3 &v1, double3 *impact=NULL, double3 *normal=NULL); +int BoxInside(const double3 &p,const double3 &bmin, const double3 &bmax) ; +int BoxIntersect(const double3 &v0, const double3 &v1, const double3 &bmin, const double3 &bmax, double3 *impact); +double DistanceBetweenLines(const double3 &ustart, const double3 &udir, const double3 &vstart, const double3 &vdir, double3 *upoint=NULL, double3 *vpoint=NULL); +double3 TriNormal(const double3 &v0, const double3 &v1, const double3 &v2); +double3 NormalOf(const double3 *vert, const int n); +Quaternion VirtualTrackBall(const double3 &cop, const double3 &cor, const double3 &dir0, const double3 &dir1); + + + + +//***************************************************** +// ** VECMATH.CPP +//***************************************************** + + +double sqr(double a) {return a*a;} +double clampf(double a) {return Min(1.0,Max(0.0,a));} + + +double Round(double a,double precision) +{ + return floor(0.5f+a/precision)*precision; +} + + +double Interpolate(const double &f0,const double &f1,double alpha) +{ + return f0*(1-alpha) + f1*alpha; +} + + +int argmin(double a[],int n) +{ + int r=0; + for(int i=1;i=1.0) { + return a; + } + double theta = acos(d); + if(theta==0.0f) { return(a);} + return a*(sin(theta-interp*theta)/sin(theta)) + b*(sin(interp*theta)/sin(theta)); +} + + +Quaternion Interpolate(const Quaternion &q0,const Quaternion &q1,double alpha) { + return slerp(q0,q1,alpha); +} + + +Quaternion YawPitchRoll( double yaw, double pitch, double roll ) +{ + roll *= DEG2RAD; + yaw *= DEG2RAD; + pitch *= DEG2RAD; + return Quaternion(double3(0.0f,0.0f,1.0f),yaw)*Quaternion(double3(1.0f,0.0f,0.0f),pitch)*Quaternion(double3(0.0f,1.0f,0.0f),roll); +} + +double Yaw( const Quaternion& q ) +{ + static double3 v; + v=q.ydir(); + return (v.y==0.0&&v.x==0.0) ? 0.0: atan2(-v.x,v.y)*RAD2DEG; +} + +double Pitch( const Quaternion& q ) +{ + static double3 v; + v=q.ydir(); + return atan2(v.z,sqrt(sqr(v.x)+sqr(v.y)))*RAD2DEG; +} + +double Roll( Quaternion q ) +{ + q = Quaternion(double3(0.0f,0.0f,1.0f),-Yaw(q)*DEG2RAD) *q; + q = Quaternion(double3(1.0f,0.0f,0.0f),-Pitch(q)*DEG2RAD) *q; + return atan2(-q.xdir().z,q.xdir().x)*RAD2DEG; +} + +double Yaw( const double3& v ) +{ + return (v.y==0.0&&v.x==0.0) ? 0.0f: atan2(-v.x,v.y)*RAD2DEG; +} + +double Pitch( const double3& v ) +{ + return atan2(v.z,sqrt(sqr(v.x)+sqr(v.y)))*RAD2DEG; +} + + +//------------- Plane -------------- + + +void Plane::Transform(const double3 &position, const Quaternion &orientation) { + // Transforms the plane to the space defined by the + // given position/orientation. + static double3 newnormal; + static double3 origin; + + newnormal = Inverse(orientation)*normal; + origin = Inverse(orientation)*(-normal*dist - position); + + normal = newnormal; + dist = -dot(newnormal, origin); +} + + + + +//--------- utility functions ------------- + +// RotationArc() +// Given two vectors v0 and v1 this function +// returns quaternion q where q*v0==v1. +// Routine taken from game programming gems. +Quaternion RotationArc(double3 v0,double3 v1){ + static Quaternion q; + v0 = normalize(v0); // Comment these two lines out if you know its not needed. + v1 = normalize(v1); // If vector is already unit length then why do it again? + double3 c = cross(v0,v1); + double d = dot(v0,v1); + if(d<=-1.0f) { return Quaternion(1,0,0,0);} // 180 about x axis + double s = sqrt((1+d)*2); + q.x = c.x / s; + q.y = c.y / s; + q.z = c.z / s; + q.w = s /2.0f; + return q; +} + + +double4x4 MatrixFromQuatVec(const Quaternion &q, const double3 &v) +{ + // builds a 4x4 transformation matrix based on orientation q and translation v + double qx2 = q.x*q.x; + double qy2 = q.y*q.y; + double qz2 = q.z*q.z; + + double qxqy = q.x*q.y; + double qxqz = q.x*q.z; + double qxqw = q.x*q.w; + double qyqz = q.y*q.z; + double qyqw = q.y*q.w; + double qzqw = q.z*q.w; + + return double4x4( + 1-2*(qy2+qz2), + 2*(qxqy+qzqw), + 2*(qxqz-qyqw), + 0 , + 2*(qxqy-qzqw), + 1-2*(qx2+qz2), + 2*(qyqz+qxqw), + 0 , + 2*(qxqz+qyqw), + 2*(qyqz-qxqw), + 1-2*(qx2+qy2), + 0 , + v.x , + v.y , + v.z , + 1.0f ); +} + + +double3 PlaneLineIntersection(const Plane &plane, const double3 &p0, const double3 &p1) +{ + // returns the point where the line p0-p1 intersects the plane n&d + static double3 dif; + dif = p1-p0; + double dn= dot(plane.normal,dif); + double t = -(plane.dist+dot(plane.normal,p0) )/dn; + return p0 + (dif*t); +} + +double3 PlaneProject(const Plane &plane, const double3 &point) +{ + return point - plane.normal * (dot(point,plane.normal)+plane.dist); +} + +double3 LineProject(const double3 &p0, const double3 &p1, const double3 &a) +{ + double3 w; + w = p1-p0; + double t= dot(w,(a-p0)) / (sqr(w.x)+sqr(w.y)+sqr(w.z)); + return p0+ w*t; +} + + +double LineProjectTime(const double3 &p0, const double3 &p1, const double3 &a) +{ + double3 w; + w = p1-p0; + double t= dot(w,(a-p0)) / (sqr(w.x)+sqr(w.y)+sqr(w.z)); + return t; +} + + + +double3 TriNormal(const double3 &v0, const double3 &v1, const double3 &v2) +{ + // return the normal of the triangle + // inscribed by v0, v1, and v2 + double3 cp=cross(v1-v0,v2-v1); + double m=magnitude(cp); + if(m==0) return double3(1,0,0); + return cp*(1.0f/m); +} + + + +int BoxInside(const double3 &p, const double3 &bmin, const double3 &bmax) +{ + return (p.x >= bmin.x && p.x <=bmax.x && + p.y >= bmin.y && p.y <=bmax.y && + p.z >= bmin.z && p.z <=bmax.z ); +} + + +int BoxIntersect(const double3 &v0, const double3 &v1, const double3 &bmin, const double3 &bmax,double3 *impact) +{ + if(BoxInside(v0,bmin,bmax)) + { + *impact=v0; + return 1; + } + if(v0.x<=bmin.x && v1.x>=bmin.x) + { + double a = (bmin.x-v0.x)/(v1.x-v0.x); + //v.x = bmin.x; + double vy = (1-a) *v0.y + a*v1.y; + double vz = (1-a) *v0.z + a*v1.z; + if(vy>=bmin.y && vy<=bmax.y && vz>=bmin.z && vz<=bmax.z) + { + impact->x = bmin.x; + impact->y = vy; + impact->z = vz; + return 1; + } + } + else if(v0.x >= bmax.x && v1.x <= bmax.x) + { + double a = (bmax.x-v0.x)/(v1.x-v0.x); + //v.x = bmax.x; + double vy = (1-a) *v0.y + a*v1.y; + double vz = (1-a) *v0.z + a*v1.z; + if(vy>=bmin.y && vy<=bmax.y && vz>=bmin.z && vz<=bmax.z) + { + impact->x = bmax.x; + impact->y = vy; + impact->z = vz; + return 1; + } + } + if(v0.y<=bmin.y && v1.y>=bmin.y) + { + double a = (bmin.y-v0.y)/(v1.y-v0.y); + double vx = (1-a) *v0.x + a*v1.x; + //v.y = bmin.y; + double vz = (1-a) *v0.z + a*v1.z; + if(vx>=bmin.x && vx<=bmax.x && vz>=bmin.z && vz<=bmax.z) + { + impact->x = vx; + impact->y = bmin.y; + impact->z = vz; + return 1; + } + } + else if(v0.y >= bmax.y && v1.y <= bmax.y) + { + double a = (bmax.y-v0.y)/(v1.y-v0.y); + double vx = (1-a) *v0.x + a*v1.x; + // vy = bmax.y; + double vz = (1-a) *v0.z + a*v1.z; + if(vx>=bmin.x && vx<=bmax.x && vz>=bmin.z && vz<=bmax.z) + { + impact->x = vx; + impact->y = bmax.y; + impact->z = vz; + return 1; + } + } + if(v0.z<=bmin.z && v1.z>=bmin.z) + { + double a = (bmin.z-v0.z)/(v1.z-v0.z); + double vx = (1-a) *v0.x + a*v1.x; + double vy = (1-a) *v0.y + a*v1.y; + // v.z = bmin.z; + if(vy>=bmin.y && vy<=bmax.y && vx>=bmin.x && vx<=bmax.x) + { + impact->x = vx; + impact->y = vy; + impact->z = bmin.z; + return 1; + } + } + else if(v0.z >= bmax.z && v1.z <= bmax.z) + { + double a = (bmax.z-v0.z)/(v1.z-v0.z); + double vx = (1-a) *v0.x + a*v1.x; + double vy = (1-a) *v0.y + a*v1.y; + // v.z = bmax.z; + if(vy>=bmin.y && vy<=bmax.y && vx>=bmin.x && vx<=bmax.x) + { + impact->x = vx; + impact->y = vy; + impact->z = bmax.z; + return 1; + } + } + return 0; +} + + +double DistanceBetweenLines(const double3 &ustart, const double3 &udir, const double3 &vstart, const double3 &vdir, double3 *upoint, double3 *vpoint) +{ + static double3 cp; + cp = normalize(cross(udir,vdir)); + + double distu = -dot(cp,ustart); + double distv = -dot(cp,vstart); + double dist = (double)fabs(distu-distv); + if(upoint) + { + Plane plane; + plane.normal = normalize(cross(vdir,cp)); + plane.dist = -dot(plane.normal,vstart); + *upoint = PlaneLineIntersection(plane,ustart,ustart+udir); + } + if(vpoint) + { + Plane plane; + plane.normal = normalize(cross(udir,cp)); + plane.dist = -dot(plane.normal,ustart); + *vpoint = PlaneLineIntersection(plane,vstart,vstart+vdir); + } + return dist; +} + + +Quaternion VirtualTrackBall(const double3 &cop, const double3 &cor, const double3 &dir1, const double3 &dir2) +{ + // routine taken from game programming gems. + // Implement track ball functionality to spin stuf on the screen + // cop center of projection + // cor center of rotation + // dir1 old mouse direction + // dir2 new mouse direction + // pretend there is a sphere around cor. Then find the points + // where dir1 and dir2 intersect that sphere. Find the + // rotation that takes the first point to the second. + double m; + // compute plane + double3 nrml = cor - cop; + double fudgefactor = 1.0f/(magnitude(nrml) * 0.25f); // since trackball proportional to distance from cop + nrml = normalize(nrml); + double dist = -dot(nrml,cor); + double3 u= PlaneLineIntersection(Plane(nrml,dist),cop,cop+dir1); + u=u-cor; + u=u*fudgefactor; + m= magnitude(u); + if(m>1) + { + u/=m; + } + else + { + u=u - (nrml * sqrt(1-m*m)); + } + double3 v= PlaneLineIntersection(Plane(nrml,dist),cop,cop+dir2); + v=v-cor; + v=v*fudgefactor; + m= magnitude(v); + if(m>1) + { + v/=m; + } + else + { + v=v - (nrml * sqrt(1-m*m)); + } + return RotationArc(u,v); +} + + +int countpolyhit=0; +int PolyHit(const double3 *vert, const int n, const double3 &v0, const double3 &v1, double3 *impact, double3 *normal) +{ + countpolyhit++; + int i; + double3 nrml(0,0,0); + for(i=0;i0) + { + return 0; + } + + static double3 the_point; + // By using the cached plane distances d0 and d1 + // we can optimize the following: + // the_point = planelineintersection(nrml,dist,v0,v1); + double a = d0/(d0-d1); + the_point = v0*(1-a) + v1*a; + + + int inside=1; + for(int j=0;inside && j= 0.0); + } + if(inside) + { + if(normal){*normal=nrml;} + if(impact){*impact=the_point;} + } + return inside; +} + +//**************************************************** +// HULL.H source code goes here +//**************************************************** +class PHullResult +{ +public: + + PHullResult(void) + { + mVcount = 0; + mIndexCount = 0; + mFaceCount = 0; + mVertices = 0; + mIndices = 0; + } + + unsigned int mVcount; + unsigned int mIndexCount; + unsigned int mFaceCount; + double *mVertices; + unsigned int *mIndices; +}; + +bool ComputeHull(unsigned int vcount,const double *vertices,PHullResult &result,unsigned int maxverts,double inflate); +void ReleaseHull(PHullResult &result); + +//***************************************************** +// HULL.cpp source code goes here +//***************************************************** + + +#define REAL3 double3 +#define REAL double + +#define COPLANAR (0) +#define UNDER (1) +#define OVER (2) +#define SPLIT (OVER|UNDER) +#define PAPERWIDTH (0.001f) +#define VOLUME_EPSILON (1e-20f) + +double planetestepsilon = PAPERWIDTH; + +#if STANDALONE +class ConvexH +#else +class ConvexH : public NxFoundation::NxAllocateable +#endif +{ + public: + class HalfEdge + { + public: + short ea; // the other half of the edge (index into edges list) + unsigned char v; // the vertex at the start of this edge (index into vertices list) + unsigned char p; // the facet on which this edge lies (index into facets list) + HalfEdge(){} + HalfEdge(short _ea,unsigned char _v, unsigned char _p):ea(_ea),v(_v),p(_p){} + }; + Array vertices; + Array edges; + Array facets; + ConvexH(int vertices_size,int edges_size,int facets_size); +}; + +typedef ConvexH::HalfEdge HalfEdge; + +ConvexH::ConvexH(int vertices_size,int edges_size,int facets_size) + :vertices(vertices_size) + ,edges(edges_size) + ,facets(facets_size) +{ + vertices.count=vertices_size; + edges.count = edges_size; + facets.count = facets_size; +} + +ConvexH *ConvexHDup(ConvexH *src) +{ +#if STANDALONE + ConvexH *dst = new ConvexH(src->vertices.count,src->edges.count,src->facets.count); +#else + ConvexH *dst = NX_NEW_MEM(ConvexH(src->vertices.count,src->edges.count,src->facets.count), CONVEX_TEMP); +#endif + + memcpy(dst->vertices.element,src->vertices.element,sizeof(double3)*src->vertices.count); + memcpy(dst->edges.element,src->edges.element,sizeof(HalfEdge)*src->edges.count); + memcpy(dst->facets.element,src->facets.element,sizeof(Plane)*src->facets.count); + return dst; +} + + +int PlaneTest(const Plane &p, const REAL3 &v) { + REAL a = dot(v,p.normal)+p.dist; + int flag = (a>planetestepsilon)?OVER:((a<-planetestepsilon)?UNDER:COPLANAR); + return flag; +} + +int SplitTest(ConvexH &convex,const Plane &plane) { + int flag=0; + for(int i=0;i= convex.edges.count || convex.edges[inext].p != convex.edges[i].p) { + inext = estart; + } + assert(convex.edges[inext].p == convex.edges[i].p); + HalfEdge &edge = convex.edges[i]; + int nb = convex.edges[i].ea; + assert(nb!=255); + if(nb==255 || nb==-1) return 0; + assert(nb!=-1); + assert(i== convex.edges[nb].ea); + } + for(i=0;i= convex.edges.count || convex.edges[i1].p != convex.edges[i].p) { + i1 = estart; + } + int i2 = i1+1; + if(i2>= convex.edges.count || convex.edges[i2].p != convex.edges[i].p) { + i2 = estart; + } + if(i==i2) continue; // i sliced tangent to an edge and created 2 meaningless edges + REAL3 localnormal = TriNormal(convex.vertices[convex.edges[i ].v], + convex.vertices[convex.edges[i1].v], + convex.vertices[convex.edges[i2].v]); + //assert(dot(localnormal,convex.facets[convex.edges[i].p].normal)>0);//Commented out on Stan Melax' advice + if(dot(localnormal,convex.facets[convex.edges[i].p].normal)<=0)return 0; + } + return 1; +} + +// back to back quads +ConvexH *test_btbq() +{ + +#if STANDALONE + ConvexH *convex = new ConvexH(4,8,2); +#else + ConvexH *convex = NX_NEW_MEM(ConvexH(4,8,2), CONVEX_TEMP); +#endif + + convex->vertices[0] = REAL3(0,0,0); + convex->vertices[1] = REAL3(1,0,0); + convex->vertices[2] = REAL3(1,1,0); + convex->vertices[3] = REAL3(0,1,0); + convex->facets[0] = Plane(REAL3(0,0,1),0); + convex->facets[1] = Plane(REAL3(0,0,-1),0); + convex->edges[0] = HalfEdge(7,0,0); + convex->edges[1] = HalfEdge(6,1,0); + convex->edges[2] = HalfEdge(5,2,0); + convex->edges[3] = HalfEdge(4,3,0); + + convex->edges[4] = HalfEdge(3,0,1); + convex->edges[5] = HalfEdge(2,3,1); + convex->edges[6] = HalfEdge(1,2,1); + convex->edges[7] = HalfEdge(0,1,1); + AssertIntact(*convex); + return convex; +} + +ConvexH *test_cube() +{ +#if STANDALONE + ConvexH *convex = new ConvexH(8,24,6); +#else + ConvexH *convex = NX_NEW_MEM(ConvexH(8,24,6), CONVEX_TEMP); +#endif + convex->vertices[0] = REAL3(0,0,0); + convex->vertices[1] = REAL3(0,0,1); + convex->vertices[2] = REAL3(0,1,0); + convex->vertices[3] = REAL3(0,1,1); + convex->vertices[4] = REAL3(1,0,0); + convex->vertices[5] = REAL3(1,0,1); + convex->vertices[6] = REAL3(1,1,0); + convex->vertices[7] = REAL3(1,1,1); + + convex->facets[0] = Plane(REAL3(-1,0,0),0); + convex->facets[1] = Plane(REAL3(1,0,0),-1); + convex->facets[2] = Plane(REAL3(0,-1,0),0); + convex->facets[3] = Plane(REAL3(0,1,0),-1); + convex->facets[4] = Plane(REAL3(0,0,-1),0); + convex->facets[5] = Plane(REAL3(0,0,1),-1); + + convex->edges[0 ] = HalfEdge(11,0,0); + convex->edges[1 ] = HalfEdge(23,1,0); + convex->edges[2 ] = HalfEdge(15,3,0); + convex->edges[3 ] = HalfEdge(16,2,0); + + convex->edges[4 ] = HalfEdge(13,6,1); + convex->edges[5 ] = HalfEdge(21,7,1); + convex->edges[6 ] = HalfEdge( 9,5,1); + convex->edges[7 ] = HalfEdge(18,4,1); + + convex->edges[8 ] = HalfEdge(19,0,2); + convex->edges[9 ] = HalfEdge( 6,4,2); + convex->edges[10] = HalfEdge(20,5,2); + convex->edges[11] = HalfEdge( 0,1,2); + + convex->edges[12] = HalfEdge(22,3,3); + convex->edges[13] = HalfEdge( 4,7,3); + convex->edges[14] = HalfEdge(17,6,3); + convex->edges[15] = HalfEdge( 2,2,3); + + convex->edges[16] = HalfEdge( 3,0,4); + convex->edges[17] = HalfEdge(14,2,4); + convex->edges[18] = HalfEdge( 7,6,4); + convex->edges[19] = HalfEdge( 8,4,4); + + convex->edges[20] = HalfEdge(10,1,5); + convex->edges[21] = HalfEdge( 5,5,5); + convex->edges[22] = HalfEdge(12,7,5); + convex->edges[23] = HalfEdge( 1,3,5); + + + return convex; +} +ConvexH *ConvexHMakeCube(const REAL3 &bmin, const REAL3 &bmax) { + ConvexH *convex = test_cube(); + convex->vertices[0] = REAL3(bmin.x,bmin.y,bmin.z); + convex->vertices[1] = REAL3(bmin.x,bmin.y,bmax.z); + convex->vertices[2] = REAL3(bmin.x,bmax.y,bmin.z); + convex->vertices[3] = REAL3(bmin.x,bmax.y,bmax.z); + convex->vertices[4] = REAL3(bmax.x,bmin.y,bmin.z); + convex->vertices[5] = REAL3(bmax.x,bmin.y,bmax.z); + convex->vertices[6] = REAL3(bmax.x,bmax.y,bmin.z); + convex->vertices[7] = REAL3(bmax.x,bmax.y,bmax.z); + + convex->facets[0] = Plane(REAL3(-1,0,0), bmin.x); + convex->facets[1] = Plane(REAL3(1,0,0), -bmax.x); + convex->facets[2] = Plane(REAL3(0,-1,0), bmin.y); + convex->facets[3] = Plane(REAL3(0,1,0), -bmax.y); + convex->facets[4] = Plane(REAL3(0,0,-1), bmin.z); + convex->facets[5] = Plane(REAL3(0,0,1), -bmax.z); + return convex; +} +ConvexH *ConvexHCrop(ConvexH &convex,const Plane &slice) +{ + int i; + int vertcountunder=0; + int vertcountover =0; + int edgecountunder=0; + int edgecountover =0; + int planecountunder=0; + int planecountover =0; + static Array vertscoplanar; // existing vertex members of convex that are coplanar + vertscoplanar.count=0; + static Array edgesplit; // existing edges that members of convex that cross the splitplane + edgesplit.count=0; + + assert(convex.edges.count<480); + + EdgeFlag edgeflag[512]; + VertFlag vertflag[256]; + PlaneFlag planeflag[128]; + HalfEdge tmpunderedges[512]; + Plane tmpunderplanes[128]; + Coplanar coplanaredges[512]; + int coplanaredges_num=0; + + Array createdverts; + // do the side-of-plane tests + for(i=0;i= convex.edges.count || convex.edges[e1].p!=currentplane) { + enextface = e1; + e1=estart; + } + HalfEdge &edge0 = convex.edges[e0]; + HalfEdge &edge1 = convex.edges[e1]; + HalfEdge &edgea = convex.edges[edge0.ea]; + + + planeside |= vertflag[edge0.v].planetest; + //if((vertflag[edge0.v].planetest & vertflag[edge1.v].planetest) == COPLANAR) { + // assert(ecop==-1); + // ecop=e; + //} + + + if(vertflag[edge0.v].planetest == OVER && vertflag[edge1.v].planetest == OVER){ + // both endpoints over plane + edgeflag[e0].undermap = -1; + } + else if((vertflag[edge0.v].planetest | vertflag[edge1.v].planetest) == UNDER) { + // at least one endpoint under, the other coplanar or under + + edgeflag[e0].undermap = under_edge_count; + tmpunderedges[under_edge_count].v = vertflag[edge0.v].undermap; + tmpunderedges[under_edge_count].p = underplanescount; + if(edge0.ea < e0) { + // connect the neighbors + assert(edgeflag[edge0.ea].undermap !=-1); + tmpunderedges[under_edge_count].ea = edgeflag[edge0.ea].undermap; + tmpunderedges[edgeflag[edge0.ea].undermap].ea = under_edge_count; + } + under_edge_count++; + } + else if((vertflag[edge0.v].planetest | vertflag[edge1.v].planetest) == COPLANAR) { + // both endpoints coplanar + // must check a 3rd point to see if UNDER + int e2 = e1+1; + if(e2>=convex.edges.count || convex.edges[e2].p!=currentplane) { + e2 = estart; + } + assert(convex.edges[e2].p==currentplane); + HalfEdge &edge2 = convex.edges[e2]; + if(vertflag[edge2.v].planetest==UNDER) { + + edgeflag[e0].undermap = under_edge_count; + tmpunderedges[under_edge_count].v = vertflag[edge0.v].undermap; + tmpunderedges[under_edge_count].p = underplanescount; + tmpunderedges[under_edge_count].ea = -1; + // make sure this edge is added to the "coplanar" list + coplanaredge = under_edge_count; + vout = vertflag[edge0.v].undermap; + vin = vertflag[edge1.v].undermap; + under_edge_count++; + } + else { + edgeflag[e0].undermap = -1; + } + } + else if(vertflag[edge0.v].planetest == UNDER && vertflag[edge1.v].planetest == OVER) { + // first is under 2nd is over + + edgeflag[e0].undermap = under_edge_count; + tmpunderedges[under_edge_count].v = vertflag[edge0.v].undermap; + tmpunderedges[under_edge_count].p = underplanescount; + if(edge0.ea < e0) { + assert(edgeflag[edge0.ea].undermap !=-1); + // connect the neighbors + tmpunderedges[under_edge_count].ea = edgeflag[edge0.ea].undermap; + tmpunderedges[edgeflag[edge0.ea].undermap].ea = under_edge_count; + vout = tmpunderedges[edgeflag[edge0.ea].undermap].v; + } + else { + Plane &p0 = convex.facets[edge0.p]; + Plane &pa = convex.facets[edgea.p]; + createdverts.Add(ThreePlaneIntersection(p0,pa,slice)); + //createdverts.Add(PlaneProject(slice,PlaneLineIntersection(slice,convex.vertices[edge0.v],convex.vertices[edgea.v]))); + //createdverts.Add(PlaneLineIntersection(slice,convex.vertices[edge0.v],convex.vertices[edgea.v])); + vout = vertcountunder++; + } + under_edge_count++; + /// hmmm something to think about: i might be able to output this edge regarless of + // wheter or not we know v-in yet. ok i;ll try this now: + tmpunderedges[under_edge_count].v = vout; + tmpunderedges[under_edge_count].p = underplanescount; + tmpunderedges[under_edge_count].ea = -1; + coplanaredge = under_edge_count; + under_edge_count++; + + if(vin!=-1) { + // we previously processed an edge where we came under + // now we know about vout as well + + // ADD THIS EDGE TO THE LIST OF EDGES THAT NEED NEIGHBOR ON PARTITION PLANE!! + } + + } + else if(vertflag[edge0.v].planetest == COPLANAR && vertflag[edge1.v].planetest == OVER) { + // first is coplanar 2nd is over + + edgeflag[e0].undermap = -1; + vout = vertflag[edge0.v].undermap; + // I hate this but i have to make sure part of this face is UNDER before ouputting this vert + int k=estart; + assert(edge0.p == currentplane); + while(!(planeside&UNDER) && k= vertcountunderold); // for debugging only + } + if(vout!=-1) { + // we previously processed an edge where we went over + // now we know vin too + // ADD THIS EDGE TO THE LIST OF EDGES THAT NEED NEIGHBOR ON PARTITION PLANE!! + } + // output edge + tmpunderedges[under_edge_count].v = vin; + tmpunderedges[under_edge_count].p = underplanescount; + edgeflag[e0].undermap = under_edge_count; + if(e0>edge0.ea) { + assert(edgeflag[edge0.ea].undermap !=-1); + // connect the neighbors + tmpunderedges[under_edge_count].ea = edgeflag[edge0.ea].undermap; + tmpunderedges[edgeflag[edge0.ea].undermap].ea = under_edge_count; + } + assert(edgeflag[e0].undermap == under_edge_count); + under_edge_count++; + } + else if(vertflag[edge0.v].planetest == OVER && vertflag[edge1.v].planetest == COPLANAR) { + // first is over next is coplanar + + edgeflag[e0].undermap = -1; + vin = vertflag[edge1.v].undermap; + if (vin==-1) return NULL; + if(vout!=-1) { + // we previously processed an edge where we came under + // now we know both endpoints + // ADD THIS EDGE TO THE LIST OF EDGES THAT NEED NEIGHBOR ON PARTITION PLANE!! + } + + } + else { + assert(0); + } + + + e0=e1; + e1++; // do the modulo at the beginning of the loop + + } while(e0!=estart) ; + e0 = enextface; + if(planeside&UNDER) { + planeflag[currentplane].undermap = underplanescount; + tmpunderplanes[underplanescount] = convex.facets[currentplane]; + underplanescount++; + } + else { + planeflag[currentplane].undermap = 0; + } + if(vout>=0 && (planeside&UNDER)) { + assert(vin>=0); + assert(coplanaredge>=0); + assert(coplanaredge!=511); + coplanaredges[coplanaredges_num].ea = coplanaredge; + coplanaredges[coplanaredges_num].v0 = vin; + coplanaredges[coplanaredges_num].v1 = vout; + coplanaredges_num++; + } + } + + // add the new plane to the mix: + if(coplanaredges_num>0) { + tmpunderplanes[underplanescount++]=slice; + } + for(i=0;i=coplanaredges_num) + { + // assert(jvertices.count;j++) + { + dmax = Max(dmax,dot(convex->vertices[j],planes[i].normal)+planes[i].dist); + dmin = Min(dmin,dot(convex->vertices[j],planes[i].normal)+planes[i].dist); + } + double dr = dmax-dmin; + if(drfacets.count;j++) + { + if(planes[i]==convex->facets[j]) + { + d=0;continue; + } + if(dot(planes[i].normal,convex->facets[j].normal)>maxdot_minang) + { + for(int k=0;kedges.count;k++) + { + if(convex->edges[k].p!=j) continue; + if(dot(convex->vertices[convex->edges[k].v],planes[i].normal)+planes[i].dist<0) + { + d=0; // so this plane wont get selected. + break; + } + } + } + } + if(d>md) + { + p=i; + md=d; + } + } + return (md>epsilon)?p:-1; +} + + + +template +inline int maxdir(const T *p,int count,const T &dir) +{ + assert(count); + int m=0; + for(int i=1;idot(p[m],dir)) m=i; + } + return m; +} + + +template +int maxdirfiltered(const T *p,int count,const T &dir,Array &allow) +{ + assert(count); + int m=-1; + for(int i=0;idot(p[m],dir)) m=i; + } + assert(m!=-1); + return m; +} + +double3 orth(const double3 &v) +{ + double3 a=cross(v,double3(0,0,1)); + double3 b=cross(v,double3(0,1,0)); + return normalize((magnitude(a)>magnitude(b))?a:b); +} + + +template +int maxdirsterid(const T *p,int count,const T &dir,Array &allow) +{ + int m=-1; + while(m==-1) + { + m = maxdirfiltered(p,count,dir,allow); + if(allow[m]==3) return m; + T u = orth(dir); + T v = cross(u,dir); + int ma=-1; + for(double x = 0.0f ; x<= 360.0f ; x+= 45.0f) + { + double s = sin(DEG2RAD*(x)); + double c = cos(DEG2RAD*(x)); + int mb = maxdirfiltered(p,count,dir+(u*s+v*c)*0.025f,allow); + if(ma==m && mb==m) + { + allow[m]=3; + return m; + } + if(ma!=-1 && ma!=mb) // Yuck - this is really ugly + { + int mc = ma; + for(double xx = x-40.0f ; xx <= x ; xx+= 5.0f) + { + double s = sin(DEG2RAD*(xx)); + double c = cos(DEG2RAD*(xx)); + int md = maxdirfiltered(p,count,dir+(u*s+v*c)*0.025f,allow); + if(mc==m && md==m) + { + allow[m]=3; + return m; + } + mc=md; + } + } + ma=mb; + } + allow[m]=0; + m=-1; + } + assert(0); + return m; +} + + + + +int operator ==(const int3 &a,const int3 &b) +{ + for(int i=0;i<3;i++) + { + if(a[i]!=b[i]) return 0; + } + return 1; +} + +int3 roll3(int3 a) +{ + int tmp=a[0]; + a[0]=a[1]; + a[1]=a[2]; + a[2]=tmp; + return a; +} +int isa(const int3 &a,const int3 &b) +{ + return ( a==b || roll3(a)==b || a==roll3(b) ); +} +int b2b(const int3 &a,const int3 &b) +{ + return isa(a,int3(b[2],b[1],b[0])); +} +int above(double3* vertices,const int3& t, const double3 &p, double epsilon) +{ + double3 n=TriNormal(vertices[t[0]],vertices[t[1]],vertices[t[2]]); + return (dot(n,p-vertices[t[0]]) > epsilon); // EPSILON??? +} +int hasedge(const int3 &t, int a,int b) +{ + for(int i=0;i<3;i++) + { + int i1= (i+1)%3; + if(t[i]==a && t[i1]==b) return 1; + } + return 0; +} +int hasvert(const int3 &t, int v) +{ + return (t[0]==v || t[1]==v || t[2]==v) ; +} +int shareedge(const int3 &a,const int3 &b) +{ + int i; + for(i=0;i<3;i++) + { + int i1= (i+1)%3; + if(hasedge(a,b[i1],b[i])) return 1; + } + return 0; +} + +class Tri; + +static Array tris; // djs: For heaven's sake!!!! + +#if STANDALONE +class Tri : public int3 +#else +class Tri : public int3, public NxFoundation::NxAllocateable +#endif +{ +public: + int3 n; + int id; + int vmax; + double rise; + Tri(int a,int b,int c):int3(a,b,c),n(-1,-1,-1) + { + id = tris.count; + tris.Add(this); + vmax=-1; + rise = 0.0f; + } + ~Tri() + { + assert(tris[id]==this); + tris[id]=NULL; + } + int &neib(int a,int b); +}; + + +int &Tri::neib(int a,int b) +{ + static int er=-1; + int i; + for(i=0;i<3;i++) + { + int i1=(i+1)%3; + int i2=(i+2)%3; + if((*this)[i]==a && (*this)[i1]==b) return n[i2]; + if((*this)[i]==b && (*this)[i1]==a) return n[i2]; + } + assert(0); + return er; +} +void b2bfix(Tri* s,Tri*t) +{ + int i; + for(i=0;i<3;i++) + { + int i1=(i+1)%3; + int i2=(i+2)%3; + int a = (*s)[i1]; + int b = (*s)[i2]; + assert(tris[s->neib(a,b)]->neib(b,a) == s->id); + assert(tris[t->neib(a,b)]->neib(b,a) == t->id); + tris[s->neib(a,b)]->neib(b,a) = t->neib(b,a); + tris[t->neib(b,a)]->neib(a,b) = s->neib(a,b); + } +} + +void removeb2b(Tri* s,Tri*t) +{ + b2bfix(s,t); + delete s; + delete t; +} + +void checkit(Tri *t) +{ + int i; + assert(tris[t->id]==t); + for(i=0;i<3;i++) + { + int i1=(i+1)%3; + int i2=(i+2)%3; + int a = (*t)[i1]; + int b = (*t)[i2]; + assert(a!=b); + assert( tris[t->n[i]]->neib(b,a) == t->id); + } +} +void extrude(Tri *t0,int v) +{ + int3 t= *t0; + int n = tris.count; +#if STANDALONE + Tri* ta = new Tri(v,t[1],t[2]); +#else + Tri* ta = NX_NEW_MEM(Tri(v,t[1],t[2]), CONVEX_TEMP); +#endif + ta->n = int3(t0->n[0],n+1,n+2); + tris[t0->n[0]]->neib(t[1],t[2]) = n+0; +#if STANDALONE + Tri* tb = new Tri(v,t[2],t[0]); +#else + Tri* tb = NX_NEW_MEM(Tri(v,t[2],t[0]), CONVEX_TEMP); +#endif + tb->n = int3(t0->n[1],n+2,n+0); + tris[t0->n[1]]->neib(t[2],t[0]) = n+1; +#if STANDALONE + Tri* tc = new Tri(v,t[0],t[1]); +#else + Tri* tc = NX_NEW_MEM(Tri(v,t[0],t[1]), CONVEX_TEMP); +#endif + tc->n = int3(t0->n[2],n+0,n+1); + tris[t0->n[2]]->neib(t[0],t[1]) = n+2; + checkit(ta); + checkit(tb); + checkit(tc); + if(hasvert(*tris[ta->n[0]],v)) removeb2b(ta,tris[ta->n[0]]); + if(hasvert(*tris[tb->n[0]],v)) removeb2b(tb,tris[tb->n[0]]); + if(hasvert(*tris[tc->n[0]],v)) removeb2b(tc,tris[tc->n[0]]); + delete t0; + +} + +Tri *extrudable(double epsilon) +{ + int i; + Tri *t=NULL; + for(i=0;iriserise)) + { + t = tris[i]; + } + } + return (t->rise >epsilon)?t:NULL ; +} + +class int4 +{ +public: + int x,y,z,w; + int4(){}; + int4(int _x,int _y, int _z,int _w){x=_x;y=_y;z=_z;w=_w;} + const int& operator[](int i) const {return (&x)[i];} + int& operator[](int i) {return (&x)[i];} +}; + + + +bool hasVolume(double3 *verts, int p0, int p1, int p2, int p3) +{ + double3 result3 = cross(verts[p1]-verts[p0], verts[p2]-verts[p0]); + if (magnitude(result3) < VOLUME_EPSILON && magnitude(result3) > -VOLUME_EPSILON) // Almost collinear or otherwise very close to each other + return false; + double result = dot(normalize(result3), verts[p3]-verts[p0]); + return (result > VOLUME_EPSILON || result < -VOLUME_EPSILON); // Returns true iff volume is significantly non-zero +} + +int4 FindSimplex(double3 *verts,int verts_count,Array &allow) +{ + double3 basis[3]; + basis[0] = double3( 0.01f, 0.02f, 1.0f ); + int p0 = maxdirsterid(verts,verts_count, basis[0],allow); + int p1 = maxdirsterid(verts,verts_count,-basis[0],allow); + basis[0] = verts[p0]-verts[p1]; + if(p0==p1 || basis[0]==double3(0,0,0)) + return int4(-1,-1,-1,-1); + basis[1] = cross(double3( 1, 0.02f, 0),basis[0]); + basis[2] = cross(double3(-0.02f, 1, 0),basis[0]); + basis[1] = normalize( (magnitude(basis[1])>magnitude(basis[2])) ? basis[1]:basis[2]); + int p2 = maxdirsterid(verts,verts_count,basis[1],allow); + if(p2 == p0 || p2 == p1) + { + p2 = maxdirsterid(verts,verts_count,-basis[1],allow); + } + if(p2 == p0 || p2 == p1) + return int4(-1,-1,-1,-1); + basis[1] = verts[p2] - verts[p0]; + basis[2] = normalize(cross(basis[1],basis[0])); + int p3 = maxdirsterid(verts,verts_count,basis[2],allow); + if(p3==p0||p3==p1||p3==p2||!hasVolume(verts, p0, p1, p2, p3)) p3 = maxdirsterid(verts,verts_count,-basis[2],allow); + if(p3==p0||p3==p1||p3==p2) + return int4(-1,-1,-1,-1); + assert(!(p0==p1||p0==p2||p0==p3||p1==p2||p1==p3||p2==p3)); + if(dot(verts[p3]-verts[p0],cross(verts[p1]-verts[p0],verts[p2]-verts[p0])) <0) {Swap(p2,p3);} + return int4(p0,p1,p2,p3); +} + +int calchullgen(double3 *verts,int verts_count, int vlimit) +{ + if(verts_count <4) return 0; + if(vlimit==0) vlimit=1000000000; + int j; + double3 bmin(*verts),bmax(*verts); + Array isextreme(verts_count); + Array allow(verts_count); + for(j=0;jn=int3(2,3,1); + Tri *t1 = new Tri(p[3],p[2],p[0]); t1->n=int3(3,2,0); + Tri *t2 = new Tri(p[0],p[1],p[3]); t2->n=int3(0,1,3); + Tri *t3 = new Tri(p[1],p[0],p[2]); t3->n=int3(1,0,2); +#else + Tri *t0 = NX_NEW_MEM(Tri(p[2],p[3],p[1]); t0->n=int3(2,3,1), CONVEX_TEMP); + Tri *t1 = NX_NEW_MEM(Tri(p[3],p[2],p[0]); t1->n=int3(3,2,0), CONVEX_TEMP); + Tri *t2 = NX_NEW_MEM(Tri(p[0],p[1],p[3]); t2->n=int3(0,1,3), CONVEX_TEMP); + Tri *t3 = NX_NEW_MEM(Tri(p[1],p[0],p[2]); t3->n=int3(1,0,2), CONVEX_TEMP); +#endif + isextreme[p[0]]=isextreme[p[1]]=isextreme[p[2]]=isextreme[p[3]]=1; + checkit(t0);checkit(t1);checkit(t2);checkit(t3); + + for(j=0;jvmax<0); + double3 n=TriNormal(verts[(*t)[0]],verts[(*t)[1]],verts[(*t)[2]]); + t->vmax = maxdirsterid(verts,verts_count,n,allow); + t->rise = dot(n,verts[t->vmax]-verts[(*t)[0]]); + } + Tri *te; + vlimit-=4; + while(vlimit >0 && (te=extrudable(epsilon))) + { + int3 ti=*te; + int v=te->vmax; + assert(!isextreme[v]); // wtf we've already done this vertex + isextreme[v]=1; + //if(v==p0 || v==p1 || v==p2 || v==p3) continue; // done these already + j=tris.count; + int newstart=j; + while(j--) { + if(!tris[j]) continue; + int3 t=*tris[j]; + if(above(verts,t,verts[v],0.01f*epsilon)) + { + extrude(tris[j],v); + } + } + // now check for those degenerate cases where we have a flipped triangle or a really skinny triangle + j=tris.count; + while(j--) + { + if(!tris[j]) continue; + if(!hasvert(*tris[j],v)) break; + int3 nt=*tris[j]; + if(above(verts,nt,center,0.01f*epsilon) || magnitude(cross(verts[nt[1]]-verts[nt[0]],verts[nt[2]]-verts[nt[1]]))< epsilon*epsilon*0.1f ) + { + Tri *nb = tris[tris[j]->n[0]]; + assert(nb);assert(!hasvert(*nb,v));assert(nb->idvmax>=0) break; + double3 n=TriNormal(verts[(*t)[0]],verts[(*t)[1]],verts[(*t)[2]]); + t->vmax = maxdirsterid(verts,verts_count,n,allow); + if(isextreme[t->vmax]) + { + t->vmax=-1; // already done that vertex - algorithm needs to be able to terminate. + } + else + { + t->rise = dot(n,verts[t->vmax]-verts[(*t)[0]]); + } + } + vlimit --; + } + return 1; +} + +int calchull(double3 *verts,int verts_count, int *&tris_out, int &tris_count,int vlimit) +{ + int rc=calchullgen(verts,verts_count, vlimit) ; + if(!rc) return 0; + Array ts; + for(int i=0;i &planes,double bevangle) +{ + int i,j; + Array bplanes; + planes.count=0; + int rc = calchullgen(verts,verts_count,vlimit); + if(!rc) return 0; + extern double minadjangle; // default is 3.0f; // in degrees - result wont have two adjacent facets within this angle of each other. + double maxdot_minang = cos(DEG2RAD*minadjangle); + for(i=0;in[j]id) continue; + Tri *s = tris[t->n[j]]; + REAL3 snormal = TriNormal(verts[(*s)[0]],verts[(*s)[1]],verts[(*s)[2]]); + if(dot(snormal,p.normal)>=cos(bevangle*DEG2RAD)) continue; + REAL3 e = verts[(*t)[(j+2)%3]] - verts[(*t)[(j+1)%3]]; + REAL3 n = (e!=REAL3(0,0,0))? cross(snormal,e)+cross(e,p.normal) : snormal+p.normal; + assert(n!=REAL3(0,0,0)); + if(n==REAL3(0,0,0)) return 0; + n=normalize(n); + bplanes.Add(Plane(n,-dot(n,verts[maxdir(verts,verts_count,n)]))); + } + } + for(i=0;imaxdot_minang) + { + // somebody has to die, keep the biggest triangle + if( area2(verts[(*ti)[0]],verts[(*ti)[1]],verts[(*ti)[2]]) < area2(verts[(*tj)[0]],verts[(*tj)[1]],verts[(*tj)[2]])) + { + delete tris[i]; tris[i]=NULL; + } + else + { + delete tris[j]; tris[j]=NULL; + } + } + } + for(i=0;imaxdot_minang) break; + } + if(j==planes.count) + { + planes.Add(bplanes[i]); + } + } + for(i=0;i maxdot_minang) + { + (*((j%2)?&bmax:&bmin)) += n * (diameter*0.5f); + break; + } + } + } + ConvexH *c = ConvexHMakeCube(REAL3(bmin),REAL3(bmax)); + int k; + while(maxplanes-- && (k=candidateplane(planes,planes_count,c,epsilon))>=0) + { + ConvexH *tmp = c; + c = ConvexHCrop(*tmp,planes[k]); + if(c==NULL) {c=tmp; break;} // might want to debug this case better!!! + if(!AssertIntact(*c)) {c=tmp; break;} // might want to debug this case better too!!! + delete tmp; + } + + assert(AssertIntact(*c)); + //return c; + faces_out = (int*)NX_ALLOC(sizeof(int)*(1+c->facets.count+c->edges.count), CONVEX_TEMP); // new int[1+c->facets.count+c->edges.count]; + faces_count_out=0; + i=0; + faces_out[faces_count_out++]=-1; + k=0; + while(iedges.count) + { + j=1; + while(j+iedges.count && c->edges[i].p==c->edges[i+j].p) { j++; } + faces_out[faces_count_out++]=j; + while(j--) + { + faces_out[faces_count_out++] = c->edges[i].v; + i++; + } + k++; + } + faces_out[0]=k; // number of faces. + assert(k==c->facets.count); + assert(faces_count_out == 1+c->facets.count+c->edges.count); + verts_out = c->vertices.element; // new double3[c->vertices.count]; + verts_count_out = c->vertices.count; + for(i=0;ivertices.count;i++) + { + verts_out[i] = double3(c->vertices[i]); + } + c->vertices.count=c->vertices.array_size=0; c->vertices.element=NULL; + delete c; + return 1; +} + +static int overhullv(double3 *verts, int verts_count,int maxplanes, + double3 *&verts_out, int &verts_count_out, int *&faces_out, int &faces_count_out ,double inflate,double bevangle,int vlimit) +{ + if(!verts_count) return 0; + extern int calchullpbev(double3 *verts,int verts_count,int vlimit, Array &planes,double bevangle) ; + Array planes; + int rc=calchullpbev(verts,verts_count,vlimit,planes,bevangle) ; + if(!rc) return 0; + return overhull(planes.element,planes.count,verts,verts_count,maxplanes,verts_out,verts_count_out,faces_out,faces_count_out,inflate); +} + + +//***************************************************** +//***************************************************** + + +bool ComputeHull(unsigned int vcount,const double *vertices,PHullResult &result,unsigned int vlimit,double inflate) +{ + + int index_count; + int *faces; + double3 *verts_out; + int verts_count_out; + + if(inflate==0.0f) + { + int *tris_out; + int tris_count; + int ret = calchull( (double3 *) vertices, (int) vcount, tris_out, tris_count, vlimit ); + if(!ret) return false; + result.mIndexCount = (unsigned int) (tris_count*3); + result.mFaceCount = (unsigned int) tris_count; + result.mVertices = (double*) vertices; + result.mVcount = (unsigned int) vcount; + result.mIndices = (unsigned int *) tris_out; + return true; + } + + int ret = overhullv((double3*)vertices,vcount,35,verts_out,verts_count_out,faces,index_count,inflate,120.0f,vlimit); + if(!ret) { + tris.SetSize(0); //have to set the size to 0 in order to protect from a "pure virtual function call" problem + return false; + } + + Array tris; + int n=faces[0]; + int k=1; + for(int i=0;i bmax[0] ) bmax[0] = v[0]; + if ( v[1] > bmax[1] ) bmax[1] = v[1]; + if ( v[2] > bmax[2] ) bmax[2] = v[2]; + } + + } + } + + double skinwidth = 0; + + if ( desc.HasHullFlag(QF_SKIN_WIDTH) ) + { + skinwidth = desc.mSkinWidth; + if ( skinwidth < 0 ) // if it is a negative skinwidth we shrink the hull points relative to the center. + { + double center[3]; + + center[0] = (bmax[0] - bmin[0])*0.5f + bmin[0]; + center[1] = (bmax[1] - bmin[1])*0.5f + bmin[1]; + center[2] = (bmax[2] - bmin[2])*0.5f + bmin[2]; + + double dx = (bmax[0]-bmin[0])*0.5f; + double dy = (bmax[1]-bmin[1])*0.5f; + double dz = (bmax[2]-bmin[2])*0.5f; + double dist = sqrt(dx*dx+dy*dy+dz*dz); + + skinwidth*=-1; // make it positive... + + double scale = 1.0f - (skinwidth/dist); + if ( scale < 0.3f ) scale = 0.3f; + for (unsigned int i=0; i bmax[j] ) bmax[j] = p[j]; + } + } + } + + double dx = bmax[0] - bmin[0]; + double dy = bmax[1] - bmin[1]; + double dz = bmax[2] - bmin[2]; + + double center[3]; + + center[0] = dx*0.5f + bmin[0]; + center[1] = dy*0.5f + bmin[1]; + center[2] = dz*0.5f + bmin[2]; + + if ( dx < EPSILON || dy < EPSILON || dz < EPSILON || svcount < 3 ) + { + + double len = FLT_MAX; + + if ( dx > EPSILON && dx < len ) len = dx; + if ( dy > EPSILON && dy < len ) len = dy; + if ( dz > EPSILON && dz < len ) len = dz; + + if ( len == FLT_MAX ) + { + dx = dy = dz = 0.01f; // one centimeter + } + else + { + if ( dx < EPSILON ) dx = len * 0.05f; // 1/5th the shortest non-zero edge. + if ( dy < EPSILON ) dy = len * 0.05f; + if ( dz < EPSILON ) dz = len * 0.05f; + } + + double x1 = center[0] - dx; + double x2 = center[0] + dx; + + double y1 = center[1] - dy; + double y2 = center[1] + dy; + + double z1 = center[2] - dz; + double z2 = center[2] + dz; + + AddPoint(vcount,vertices,x1,y1,z1); + AddPoint(vcount,vertices,x2,y1,z1); + AddPoint(vcount,vertices,x2,y2,z1); + AddPoint(vcount,vertices,x1,y2,z1); + AddPoint(vcount,vertices,x1,y1,z2); + AddPoint(vcount,vertices,x2,y1,z2); + AddPoint(vcount,vertices,x2,y2,z2); + AddPoint(vcount,vertices,x1,y2,z2); + + return true; // return cube + + + } + else + { + if ( scale ) + { + scale[0] = dx; + scale[1] = dy; + scale[2] = dz; + + recip[0] = 1 / dx; + recip[1] = 1 / dy; + recip[2] = 1 / dz; + + center[0]*=recip[0]; + center[1]*=recip[1]; + center[2]*=recip[2]; + + } + + } + + + + vtx = (const char *) svertices; + + for (unsigned int i=0; i dist2 ) + { + v[0] = px; + v[1] = py; + v[2] = pz; + } + + break; + } + } + + if ( j == vcount ) + { + double *dest = &vertices[vcount*3]; + dest[0] = px; + dest[1] = py; + dest[2] = pz; + vcount++; + } + } + } + + // ok..now make sure we didn't prune so many vertices it is now invalid. + if ( 1 ) + { + double bmin[3] = { FLT_MAX, FLT_MAX, FLT_MAX }; + double bmax[3] = { -FLT_MAX, -FLT_MAX, -FLT_MAX }; + + for (unsigned int i=0; i bmax[j] ) bmax[j] = p[j]; + } + } + + double dx = bmax[0] - bmin[0]; + double dy = bmax[1] - bmin[1]; + double dz = bmax[2] - bmin[2]; + + if ( dx < EPSILON || dy < EPSILON || dz < EPSILON || vcount < 3) + { + double cx = dx*0.5f + bmin[0]; + double cy = dy*0.5f + bmin[1]; + double cz = dz*0.5f + bmin[2]; + + double len = FLT_MAX; + + if ( dx >= EPSILON && dx < len ) len = dx; + if ( dy >= EPSILON && dy < len ) len = dy; + if ( dz >= EPSILON && dz < len ) len = dz; + + if ( len == FLT_MAX ) + { + dx = dy = dz = 0.01f; // one centimeter + } + else + { + if ( dx < EPSILON ) dx = len * 0.05f; // 1/5th the shortest non-zero edge. + if ( dy < EPSILON ) dy = len * 0.05f; + if ( dz < EPSILON ) dz = len * 0.05f; + } + + double x1 = cx - dx; + double x2 = cx + dx; + + double y1 = cy - dy; + double y2 = cy + dy; + + double z1 = cz - dz; + double z2 = cz + dz; + + vcount = 0; // add box + + AddPoint(vcount,vertices,x1,y1,z1); + AddPoint(vcount,vertices,x2,y1,z1); + AddPoint(vcount,vertices,x2,y2,z1); + AddPoint(vcount,vertices,x1,y2,z1); + AddPoint(vcount,vertices,x1,y1,z2); + AddPoint(vcount,vertices,x2,y1,z2); + AddPoint(vcount,vertices,x2,y2,z2); + AddPoint(vcount,vertices,x1,y2,z2); + + return true; + } + } + + return true; +} + +void HullLibrary::BringOutYourDead(const double *verts,unsigned int vcount, double *overts,unsigned int &ocount,unsigned int *indices,unsigned indexcount) +{ + unsigned int *used = (unsigned int *)NX_ALLOC(sizeof(unsigned int)*vcount, CONVEX_TEMP ); + memset(used,0,sizeof(unsigned int)*vcount); + + ocount = 0; + + for (unsigned int i=0; i= 0 && v < vcount ); + + if ( used[v] ) // if already remapped + { + indices[i] = used[v]-1; // index to new array + } + else + { + + indices[i] = ocount; // new index mapping + + overts[ocount*3+0] = verts[v*3+0]; // copy old vert to new vert array + overts[ocount*3+1] = verts[v*3+1]; + overts[ocount*3+2] = verts[v*3+2]; + + ocount++; // increment output vert count + + assert( ocount >=0 && ocount <= vcount ); + + used[v] = ocount; // assign new index remapping + } + } + + NX_FREE(used); +} + + +//================================================================================== +HullError HullLibrary::CreateTriangleMesh(HullResult &answer,ConvexHullTriangleInterface *iface) +{ + HullError ret = QE_FAIL; + + + const double *p = answer.mOutputVertices; + const unsigned int *idx = answer.mIndices; + unsigned int fcount = answer.mNumFaces; + + if ( p && idx && fcount ) + { + ret = QE_OK; + + for (unsigned int i=0; iConvexHullTriangle(v3,v2,v1); +} + +//================================================================================== +double HullLibrary::ComputeNormal(double *n,const double *A,const double *B,const double *C) +{ + double vx,vy,vz,wx,wy,wz,vw_x,vw_y,vw_z,mag; + + vx = (B[0] - C[0]); + vy = (B[1] - C[1]); + vz = (B[2] - C[2]); + + wx = (A[0] - B[0]); + wy = (A[1] - B[1]); + wz = (A[2] - B[2]); + + vw_x = vy * wz - vz * wy; + vw_y = vz * wx - vx * wz; + vw_z = vx * wy - vy * wx; + + mag = sqrt((vw_x * vw_x) + (vw_y * vw_y) + (vw_z * vw_z)); + + if ( mag < 0.000001f ) + { + mag = 0; + } + else + { + mag = 1.0f/mag; + } + + n[0] = vw_x * mag; + n[1] = vw_y * mag; + n[2] = vw_z * mag; + + return mag; +} + + + +}; diff --git a/convex_decomposition/ConvexDecomposition/ConvexDecomposition/cd_hull.h b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/cd_hull.h new file mode 100644 index 0000000..68fb72a --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/cd_hull.h @@ -0,0 +1,250 @@ +#ifndef HULL_LIB_H + +#define HULL_LIB_H + + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + + +namespace ConvexDecomposition +{ + +class HullResult +{ +public: + HullResult(void) + { + mPolygons = true; + mNumOutputVertices = 0; + mOutputVertices = 0; + mNumFaces = 0; + mNumIndices = 0; + mIndices = 0; + } + bool mPolygons; // true if indices represents polygons, false indices are triangles + unsigned int mNumOutputVertices; // number of vertices in the output hull + double *mOutputVertices; // array of vertices, 3 doubles each x,y,z + unsigned int mNumFaces; // the number of faces produced + unsigned int mNumIndices; // the total number of indices + unsigned int *mIndices; // pointer to indices. + +// If triangles, then indices are array indexes into the vertex list. +// If polygons, indices are in the form (number of points in face) (p1, p2, p3, ..) etc.. +}; + +class FHullResult +{ +public: + FHullResult(const HullResult &r) + { + mPolygons = r.mPolygons; + mNumOutputVertices = r.mNumOutputVertices; + mNumFaces = r.mNumFaces; + mNumIndices = r.mNumIndices; + mIndices = 0; + mOutputVertices = 0; + if ( mNumIndices ) + { + mIndices = new unsigned int[mNumIndices]; + memcpy(mIndices,r.mIndices,sizeof(unsigned int)*mNumIndices); + } + if ( mNumOutputVertices ) + { + mOutputVertices = new float[mNumOutputVertices*3]; + const double *src = r.mOutputVertices; + float *dst = mOutputVertices; + for (unsigned int i=0; i +#include +#include + +namespace ConvexDecomposition +{ + + +const double DEG_TO_RAD = ((2.0f * 3.14152654f) / 360.0f); +const double RAD_TO_DEG = (360.0f / (2.0f * 3.141592654f)); + +template class Vector3d +{ +public: + Vector3d(void) { }; // null constructor, does not inialize point. + + Vector3d(const Vector3d &a) // constructor copies existing vector. + { + x = a.x; + y = a.y; + z = a.z; + }; + + Vector3d(Type a,Type b,Type c) // construct with initial point. + { + x = a; + y = b; + z = c; + }; + + Vector3d(const double *t) + { + x = t[0]; + y = t[1]; + z = t[2]; + }; + + Vector3d(const int *t) + { + x = t[0]; + y = t[1]; + z = t[2]; + }; + + bool operator==(const Vector3d &a) const + { + return( a.x == x && a.y == y && a.z == z ); + }; + + bool operator!=(const Vector3d &a) const + { + return( a.x != x || a.y != y || a.z != z ); + }; + +// Operators + Vector3d& operator = (const Vector3d& A) // ASSIGNMENT (=) + { x=A.x; y=A.y; z=A.z; + return(*this); }; + + Vector3d operator + (const Vector3d& A) const // ADDITION (+) + { Vector3d Sum(x+A.x, y+A.y, z+A.z); + return(Sum); }; + + Vector3d operator - (const Vector3d& A) const // SUBTRACTION (-) + { Vector3d Diff(x-A.x, y-A.y, z-A.z); + return(Diff); }; + + Vector3d operator * (const double s) const // MULTIPLY BY SCALAR (*) + { Vector3d Scaled(x*s, y*s, z*s); + return(Scaled); }; + + + Vector3d operator + (const double s) const // ADD CONSTANT TO ALL 3 COMPONENTS (*) + { Vector3d Scaled(x+s, y+s, z+s); + return(Scaled); }; + + + + + Vector3d operator / (const double s) const // DIVIDE BY SCALAR (/) + { + double r = 1.0f / s; + Vector3d Scaled(x*r, y*r, z*r); + return(Scaled); + }; + + void operator /= (Type A) // ACCUMULATED VECTOR ADDITION (/=) + { x/=A; y/=A; z/=A; }; + + void operator += (const Vector3d A) // ACCUMULATED VECTOR ADDITION (+=) + { x+=A.x; y+=A.y; z+=A.z; }; + void operator -= (const Vector3d A) // ACCUMULATED VECTOR SUBTRACTION (+=) + { x-=A.x; y-=A.y; z-=A.z; }; + void operator *= (const double s) // ACCUMULATED SCALAR MULTIPLICATION (*=) (bpc 4/24/2000) + {x*=s; y*=s; z*=s;} + + void operator += (const double A) // ACCUMULATED VECTOR ADDITION (+=) + { x+=A; y+=A; z+=A; }; + + + Vector3d operator - (void) const // NEGATION (-) + { Vector3d Negated(-x, -y, -z); + return(Negated); }; + + Type operator [] (const int i) const // ALLOWS VECTOR ACCESS AS AN ARRAY. + { return( (i==0)?x:((i==1)?y:z) ); }; + Type & operator [] (const int i) + { return( (i==0)?x:((i==1)?y:z) ); }; +// + + // accessor methods. + Type GetX(void) const { return x; }; + Type GetY(void) const { return y; }; + Type GetZ(void) const { return z; }; + + Type X(void) const { return x; }; + Type Y(void) const { return y; }; + Type Z(void) const { return z; }; + + void SetX(Type t) { x = t; }; + void SetY(Type t) { y = t; }; + void SetZ(Type t) { z = t; }; + + bool IsSame(const Vector3d &v,double epsilon) const + { + double dx = fabsf( x - v.x ); + if ( dx > epsilon ) return false; + double dy = fabsf( y - v.y ); + if ( dy > epsilon ) return false; + double dz = fabsf( z - v.z ); + if ( dz > epsilon ) return false; + return true; + } + + + double ComputeNormal(const Vector3d &A, + const Vector3d &B, + const Vector3d &C) + { + double vx,vy,vz,wx,wy,wz,vw_x,vw_y,vw_z,mag; + + vx = (B.x - C.x); + vy = (B.y - C.y); + vz = (B.z - C.z); + + wx = (A.x - B.x); + wy = (A.y - B.y); + wz = (A.z - B.z); + + vw_x = vy * wz - vz * wy; + vw_y = vz * wx - vx * wz; + vw_z = vx * wy - vy * wx; + + mag = sqrtf((vw_x * vw_x) + (vw_y * vw_y) + (vw_z * vw_z)); + + if ( mag < 0.000001f ) + { + mag = 0; + } + else + { + mag = 1.0f/mag; + } + + x = vw_x * mag; + y = vw_y * mag; + z = vw_z * mag; + + return mag; + } + + + void ScaleSumScale(double c0,double c1,const Vector3d &pos) + { + x = (x*c0) + (pos.x*c1); + y = (y*c0) + (pos.y*c1); + z = (z*c0) + (pos.z*c1); + } + + void SwapYZ(void) + { + double t = y; + y = z; + z = t; + }; + + void Get(Type *v) const + { + v[0] = x; + v[1] = y; + v[2] = z; + }; + + void Set(const int *p) + { + x = (Type) p[0]; + y = (Type) p[1]; + z = (Type) p[2]; + } + + void Set(const double *p) + { + x = (Type) p[0]; + y = (Type) p[1]; + z = (Type) p[2]; + } + + + void Set(Type a,Type b,Type c) + { + x = a; + y = b; + z = c; + }; + + void Zero(void) + { + x = y = z = 0; + }; + + const Type* Ptr() const { return &x; } + Type* Ptr() { return &x; } + + +// return -(*this). + Vector3d negative(void) const + { + Vector3d result; + result.x = -x; + result.y = -y; + result.z = -z; + return result; + } + + Type Magnitude(void) const + { + return Type(sqrt(x * x + y * y + z * z)); + }; + + Type FastMagnitude(void) const + { + return Type(sqrt(x * x + y * y + z * z)); + }; + + Type FasterMagnitude(void) const + { + return Type(sqrt(x * x + y * y + z * z)); + }; + + void Lerp(const Vector3d& from,const Vector3d& to,double slerp) + { + x = ((to.x - from.x) * slerp) + from.x; + y = ((to.y - from.y) * slerp) + from.y; + z = ((to.z - from.z) * slerp) + from.z; + }; + + // Highly specialized interpolate routine. Will compute the interpolated position + // shifted forward or backwards along the ray defined between (from) and (to). + // Reason for existance is so that when a bullet collides with a wall, for + // example, you can generate a graphic effect slightly *before* it hit the + // wall so that the effect doesn't sort into the wall itself. + void Interpolate(const Vector3d &from,const Vector3d &to,double offset) + { + x = to.x-from.x; + y = to.y-from.y; + z = to.z-from.z; + double d = sqrtf( x*x + y*y + z*z ); + double recip = 1.0f / d; + x*=recip; + y*=recip; + z*=recip; // normalize vector + d+=offset; // shift along ray + x = x*d + from.x; + y = y*d + from.y; + z = z*d + from.z; + }; + + bool BinaryEqual(const Vector3d &p) const + { + const int *source = (const int *) &x; + const int *dest = (const int *) &p.x; + + if ( source[0] == dest[0] && + source[1] == dest[1] && + source[2] == dest[2] ) return true; + + return false; + }; + + bool BinaryEqual(const Vector3d &p) const + { + if ( x == p.x && y == p.y && z == p.z ) return true; + return false; + } + + +/** Computes the reflection vector between two vectors.*/ + void Reflection(const Vector3d &a,const Vector3d &b)// compute reflection vector. + { + Vector3d c; + Vector3d d; + + double dot = a.Dot(b) * 2.0f; + + c = b * dot; + + d = c - a; + + x = -d.x; + y = -d.y; + z = -d.z; + }; + + void AngleAxis(Type angle,const Vector3d& axis) + { + x = axis.x*angle; + y = axis.y*angle; + z = axis.z*angle; + }; + + Type Length(void) const // length of vector. + { + return Type(sqrt( x*x + y*y + z*z )); + }; + + + double ComputePlane(const Vector3d &A, + const Vector3d &B, + const Vector3d &C) + { + double vx,vy,vz,wx,wy,wz,vw_x,vw_y,vw_z,mag; + + vx = (B.x - C.x); + vy = (B.y - C.y); + vz = (B.z - C.z); + + wx = (A.x - B.x); + wy = (A.y - B.y); + wz = (A.z - B.z); + + vw_x = vy * wz - vz * wy; + vw_y = vz * wx - vx * wz; + vw_z = vx * wy - vy * wx; + + mag = sqrt((vw_x * vw_x) + (vw_y * vw_y) + (vw_z * vw_z)); + + if ( mag < 0.000001f ) + { + mag = 0; + } + else + { + mag = 1.0f/mag; + } + + x = vw_x * mag; + y = vw_y * mag; + z = vw_z * mag; + + + double D = 0.0f - ((x*A.x)+(y*A.y)+(z*A.z)); + + return D; + } + + + Type FastLength(void) const // length of vector. + { + return Type(sqrt( x*x + y*y + z*z )); + }; + + + Type FasterLength(void) const // length of vector. + { + return Type(sqrt( x*x + y*y + z*z )); + }; + + Type Length2(void) const // squared distance, prior to square root. + { + Type l2 = x*x+y*y+z*z; + return l2; + }; + + Type Distance(const Vector3d &a) const // distance between two points. + { + Vector3d d(a.x-x,a.y-y,a.z-z); + return d.Length(); + } + + Type FastDistance(const Vector3d &a) const // distance between two points. + { + Vector3d d(a.x-x,a.y-y,a.z-z); + return d.FastLength(); + } + + Type FasterDistance(const Vector3d &a) const // distance between two points. + { + Vector3d d(a.x-x,a.y-y,a.z-z); + return d.FasterLength(); + } + + + Type DistanceXY(const Vector3d &a) const + { + double dx = a.x - x; + double dy = a.y - y; + double dist = dx*dx + dy*dy; + return dist; + } + + Type Distance2(const Vector3d &a) const // squared distance. + { + double dx = a.x - x; + double dy = a.y - y; + double dz = a.z - z; + return dx*dx + dy*dy + dz*dz; + }; + + Type Partial(const Vector3d &p) const + { + return (x*p.y) - (p.x*y); + } + + Type Area(const Vector3d &p1,const Vector3d &p2) const + { + Type A = Partial(p1); + A+= p1.Partial(p2); + A+= p2.Partial(*this); + return A*0.5f; + } + + inline double Normalize(void) // normalize to a unit vector, returns distance. + { + double d = sqrtf( static_cast< double >( x*x + y*y + z*z ) ); + if ( d > 0 ) + { + double r = 1.0f / d; + x *= r; + y *= r; + z *= r; + } + else + { + x = y = z = 1; + } + return d; + }; + + inline double FastNormalize(void) // normalize to a unit vector, returns distance. + { + double d = sqrt( static_cast< double >( x*x + y*y + z*z ) ); + if ( d > 0 ) + { + double r = 1.0f / d; + x *= r; + y *= r; + z *= r; + } + else + { + x = y = z = 1; + } + return d; + }; + + inline double FasterNormalize(void) // normalize to a unit vector, returns distance. + { + double d = sqrt( static_cast< double >( x*x + y*y + z*z ) ); + if ( d > 0 ) + { + double r = 1.0f / d; + x *= r; + y *= r; + z *= r; + } + else + { + x = y = z = 1; + } + return d; + }; + + + + + Type Dot(const Vector3d &a) const // computes dot product. + { + return (x * a.x + y * a.y + z * a.z ); + }; + + + Vector3d Cross( const Vector3d& other ) const + { + Vector3d result( y*other.z - z*other.y, z*other.x - x*other.z, x*other.y - y*other.x ); + + return result; + } + + void Cross(const Vector3d &a,const Vector3d &b) // cross two vectors result in this one. + { + x = a.y*b.z - a.z*b.y; + y = a.z*b.x - a.x*b.z; + z = a.x*b.y - a.y*b.x; + }; + + /******************************************/ + // Check if next edge (b to c) turns inward + // + // Edge from a to b is already in face + // Edge from b to c is being considered for addition to face + /******************************************/ + bool Concave(const Vector3d& a,const Vector3d& b) + { + double vx,vy,vz,wx,wy,wz,vw_x,vw_y,vw_z,mag,nx,ny,nz,mag_a,mag_b; + + wx = b.x - a.x; + wy = b.y - a.y; + wz = b.z - a.z; + + mag_a = (double) sqrtf((wx * wx) + (wy * wy) + (wz * wz)); + + vx = x - b.x; + vy = y - b.y; + vz = z - b.z; + + mag_b = (double) sqrtf((vx * vx) + (vy * vy) + (vz * vz)); + + vw_x = (vy * wz) - (vz * wy); + vw_y = (vz * wx) - (vx * wz); + vw_z = (vx * wy) - (vy * wx); + + mag = (double) sqrtf((vw_x * vw_x) + (vw_y * vw_y) + (vw_z * vw_z)); + + // Check magnitude of cross product, which is a sine function + // i.e., mag (a x b) = mag (a) * mag (b) * sin (theta); + // If sin (theta) small, then angle between edges is very close to + // 180, which we may want to call a concavity. Setting the + // CONCAVITY_TOLERANCE value greater than about 0.01 MAY cause + // face consolidation to get stuck on particular face. Most meshes + // convert properly with a value of 0.0 + + if (mag/(mag_a*mag_b) <= 0.0f ) return true; + + mag = 1.0f / mag; + + nx = vw_x * mag; + ny = vw_y * mag; + nz = vw_z * mag; + + // Dot product of tri normal with cross product result will + // yield positive number if edges are convex (+1.0 if two tris + // are coplanar), negative number if edges are concave (-1.0 if + // two tris are coplanar.) + + mag = ( x * nx) + ( y * ny) + ( z * nz); + + if (mag > 0.0f ) return false; + + return(true); + }; + + bool PointTestXY(const Vector3d &i,const Vector3d &j) const + { + if (((( i.y <= y ) && ( y < j.y )) || + (( j.y <= y ) && ( y < i.y ))) && + ( x < (j.x - i.x) * (y - i.y) / (j.y - i.y) + i.x)) return true; + return false; + } + + // test to see if this point is inside the triangle specified by + // these three points on the X/Y plane. + bool PointInTriXY(const Vector3d &p1, + const Vector3d &p2, + const Vector3d &p3) const + { + double ax = p3.x - p2.x; + double ay = p3.y - p2.y; + double bx = p1.x - p3.x; + double by = p1.y - p3.y; + double cx = p2.x - p1.x; + double cy = p2.y - p1.y; + double apx = x - p1.x; + double apy = y - p1.y; + double bpx = x - p2.x; + double bpy = y - p2.y; + double cpx = x - p3.x; + double cpy = y - p3.y; + + double aCROSSbp = ax*bpy - ay*bpx; + double cCROSSap = cx*apy - cy*apx; + double bCROSScp = bx*cpy - by*cpx; + + return ((aCROSSbp >= 0.0f) && (bCROSScp >= 0.0f) && (cCROSSap >= 0.0f)); + }; + + // test to see if this point is inside the triangle specified by + // these three points on the X/Y plane. + bool PointInTriYZ(const Vector3d &p1, + const Vector3d &p2, + const Vector3d &p3) const + { + double ay = p3.y - p2.y; + double az = p3.z - p2.z; + double by = p1.y - p3.y; + double bz = p1.z - p3.z; + double cy = p2.y - p1.y; + double cz = p2.z - p1.z; + double apy = y - p1.y; + double apz = z - p1.z; + double bpy = y - p2.y; + double bpz = z - p2.z; + double cpy = y - p3.y; + double cpz = z - p3.z; + + double aCROSSbp = ay*bpz - az*bpy; + double cCROSSap = cy*apz - cz*apy; + double bCROSScp = by*cpz - bz*cpy; + + return ((aCROSSbp >= 0.0f) && (bCROSScp >= 0.0f) && (cCROSSap >= 0.0f)); + }; + + + // test to see if this point is inside the triangle specified by + // these three points on the X/Y plane. + bool PointInTriXZ(const Vector3d &p1, + const Vector3d &p2, + const Vector3d &p3) const + { + double az = p3.z - p2.z; + double ax = p3.x - p2.x; + double bz = p1.z - p3.z; + double bx = p1.x - p3.x; + double cz = p2.z - p1.z; + double cx = p2.x - p1.x; + double apz = z - p1.z; + double apx = x - p1.x; + double bpz = z - p2.z; + double bpx = x - p2.x; + double cpz = z - p3.z; + double cpx = x - p3.x; + + double aCROSSbp = az*bpx - ax*bpz; + double cCROSSap = cz*apx - cx*apz; + double bCROSScp = bz*cpx - bx*cpz; + + return ((aCROSSbp >= 0.0f) && (bCROSScp >= 0.0f) && (cCROSSap >= 0.0f)); + }; + + // Given a point and a line (defined by two points), compute the closest point + // in the line. (The line is treated as infinitely long.) + void NearestPointInLine(const Vector3d &point, + const Vector3d &line0, + const Vector3d &line1) + { + Vector3d &nearestPoint = *this; + Vector3d lineDelta = line1 - line0; + + // Handle degenerate lines + if ( lineDelta == Vector3d(0, 0, 0) ) + { + nearestPoint = line0; + } + else + { + double delta = (point-line0).Dot(lineDelta) / (lineDelta).Dot(lineDelta); + nearestPoint = line0 + delta*lineDelta; + } + } + + // Given a point and a line segment (defined by two points), compute the closest point + // in the line. Cap the point at the endpoints of the line segment. + void NearestPointInLineSegment(const Vector3d &point, + const Vector3d &line0, + const Vector3d &line1) + { + Vector3d &nearestPoint = *this; + Vector3d lineDelta = line1 - line0; + + // Handle degenerate lines + if ( lineDelta == Vector3d(0, 0, 0) ) + { + nearestPoint = line0; + } + else + { + double delta = (point-line0).Dot(lineDelta) / (lineDelta).Dot(lineDelta); + + // Clamp the point to conform to the segment's endpoints + if ( delta < 0 ) + delta = 0; + else if ( delta > 1 ) + delta = 1; + + nearestPoint = line0 + delta*lineDelta; + } + } + + // Given a point and a plane (defined by three points), compute the closest point + // in the plane. (The plane is unbounded.) + void NearestPointInPlane(const Vector3d &point, + const Vector3d &triangle0, + const Vector3d &triangle1, + const Vector3d &triangle2) + { + Vector3d &nearestPoint = *this; + Vector3d lineDelta0 = triangle1 - triangle0; + Vector3d lineDelta1 = triangle2 - triangle0; + Vector3d pointDelta = point - triangle0; + Vector3d normal; + + // Get the normal of the polygon (doesn't have to be a unit vector) + normal.Cross(lineDelta0, lineDelta1); + + double delta = normal.Dot(pointDelta) / normal.Dot(normal); + nearestPoint = point - delta*normal; + } + + // Given a point and a plane (defined by a coplanar point and a normal), compute the closest point + // in the plane. (The plane is unbounded.) + void NearestPointInPlane(const Vector3d &point, + const Vector3d &planePoint, + const Vector3d &planeNormal) + { + Vector3d &nearestPoint = *this; + Vector3d pointDelta = point - planePoint; + + double delta = planeNormal.Dot(pointDelta) / planeNormal.Dot(planeNormal); + nearestPoint = point - delta*planeNormal; + } + + // Given a point and a triangle (defined by three points), compute the closest point + // in the triangle. Clamp the point so it's confined to the area of the triangle. + void NearestPointInTriangle(const Vector3d &point, + const Vector3d &triangle0, + const Vector3d &triangle1, + const Vector3d &triangle2) + { + static const Vector3d zeroVector(0, 0, 0); + + Vector3d &nearestPoint = *this; + + Vector3d lineDelta0 = triangle1 - triangle0; + Vector3d lineDelta1 = triangle2 - triangle0; + + // Handle degenerate triangles + if ( (lineDelta0 == zeroVector) || (lineDelta1 == zeroVector) ) + { + nearestPoint.NearestPointInLineSegment(point, triangle1, triangle2); + } + else if ( lineDelta0 == lineDelta1 ) + { + nearestPoint.NearestPointInLineSegment(point, triangle0, triangle1); + } + + else + { + static Vector3d axis[3]; + axis[0].NearestPointInLine(triangle0, triangle1, triangle2); + axis[1].NearestPointInLine(triangle1, triangle0, triangle2); + axis[2].NearestPointInLine(triangle2, triangle0, triangle1); + + Type axisDot[3]; + axisDot[0] = (triangle0-axis[0]).Dot(point-axis[0]); + axisDot[1] = (triangle1-axis[1]).Dot(point-axis[1]); + axisDot[2] = (triangle2-axis[2]).Dot(point-axis[2]); + + bool bForce = true; + Type bestMagnitude2 = 0; + Type closeMagnitude2; + Vector3d closePoint; + + if ( axisDot[0] < 0 ) + { + closePoint.NearestPointInLineSegment(point, triangle1, triangle2); + closeMagnitude2 = point.Distance2(closePoint); + if ( bForce || (bestMagnitude2 > closeMagnitude2) ) + { + bForce = false; + bestMagnitude2 = closeMagnitude2; + nearestPoint = closePoint; + } + } + if ( axisDot[1] < 0 ) + { + closePoint.NearestPointInLineSegment(point, triangle0, triangle2); + closeMagnitude2 = point.Distance2(closePoint); + if ( bForce || (bestMagnitude2 > closeMagnitude2) ) + { + bForce = false; + bestMagnitude2 = closeMagnitude2; + nearestPoint = closePoint; + } + } + if ( axisDot[2] < 0 ) + { + closePoint.NearestPointInLineSegment(point, triangle0, triangle1); + closeMagnitude2 = point.Distance2(closePoint); + if ( bForce || (bestMagnitude2 > closeMagnitude2) ) + { + bForce = false; + bestMagnitude2 = closeMagnitude2; + nearestPoint = closePoint; + } + } + + // If bForce is true at this point, it means the nearest point lies + // inside the triangle; use the nearest-point-on-a-plane equation + if ( bForce ) + { + Vector3d normal; + + // Get the normal of the polygon (doesn't have to be a unit vector) + normal.Cross(lineDelta0, lineDelta1); + + Vector3d pointDelta = point - triangle0; + double delta = normal.Dot(pointDelta) / normal.Dot(normal); + + nearestPoint = point - delta*normal; + } + } + } + + +//private: + + Type x; + Type y; + Type z; +}; + + +template class Vector2d +{ +public: + Vector2d(void) { }; // null constructor, does not inialize point. + + Vector2d(const Vector2d &a) // constructor copies existing vector. + { + x = a.x; + y = a.y; + }; + + Vector2d(const double *t) + { + x = t[0]; + y = t[1]; + }; + + + Vector2d(Type a,Type b) // construct with initial point. + { + x = a; + y = b; + }; + + const Type* Ptr() const { return &x; } + Type* Ptr() { return &x; } + + Vector2d & operator+=(const Vector2d &a) // += operator. + { + x+=a.x; + y+=a.y; + return *this; + }; + + Vector2d & operator-=(const Vector2d &a) + { + x-=a.x; + y-=a.y; + return *this; + }; + + Vector2d & operator*=(const Vector2d &a) + { + x*=a.x; + y*=a.y; + return *this; + }; + + Vector2d & operator/=(const Vector2d &a) + { + x/=a.x; + y/=a.y; + return *this; + }; + + bool operator==(const Vector2d &a) const + { + if ( a.x == x && a.y == y ) return true; + return false; + }; + + bool operator!=(const Vector2d &a) const + { + if ( a.x != x || a.y != y ) return true; + return false; + }; + + Vector2d operator+(Vector2d a) const + { + a.x+=x; + a.y+=y; + return a; + }; + + Vector2d operator-(Vector2d a) const + { + a.x = x-a.x; + a.y = y-a.y; + return a; + }; + + Vector2d operator - (void) const + { + return negative(); + }; + + Vector2d operator*(Vector2d a) const + { + a.x*=x; + a.y*=y; + return a; + }; + + Vector2d operator*(Type c) const + { + Vector2d a; + + a.x = x * c; + a.y = y * c; + + return a; + }; + + Vector2d operator/(Vector2d a) const + { + a.x = x/a.x; + a.y = y/a.y; + return a; + }; + + + Type Dot(const Vector2d &a) const // computes dot product. + { + return (x * a.x + y * a.y ); + }; + + Type GetX(void) const { return x; }; + Type GetY(void) const { return y; }; + + void SetX(Type t) { x = t; }; + void SetY(Type t) { y = t; }; + + void Set(Type a,Type b) + { + x = a; + y = b; + }; + + void Zero(void) + { + x = 0; + y = 0; + }; + + Vector2d negative(void) const + { + Vector2d result; + result.x = -x; + result.y = -y; + return result; + } + + Type magnitude(void) const + { + return (Type) sqrtf(x * x + y * y ); + } + + Type fastmagnitude(void) const + { + return (Type) sqrt(x * x + y * y ); + } + + Type fastermagnitude(void) const + { + return (Type) sqrt( x * x + y * y ); + } + + void Reflection(Vector2d &a,Vector2d &b); // compute reflection vector. + + Type Length(void) const // length of vector. + { + return Type(sqrtf( x*x + y*y )); + }; + + Type FastLength(void) const // length of vector. + { + return Type(sqrt( x*x + y*y )); + }; + + Type FasterLength(void) const // length of vector. + { + return Type(sqrt( x*x + y*y )); + }; + + Type Length2(void) // squared distance, prior to square root. + { + return x*x+y*y; + } + + Type Distance(const Vector2d &a) const // distance between two points. + { + Type dx = a.x - x; + Type dy = a.y - y; + Type d = dx*dx+dy*dy; + return sqrtf(d); + }; + + Type FastDistance(const Vector2d &a) const // distance between two points. + { + Type dx = a.x - x; + Type dy = a.y - y; + Type d = dx*dx+dy*dy; + return sqrt(d); + }; + + Type FasterDistance(const Vector2d &a) const // distance between two points. + { + Type dx = a.x - x; + Type dy = a.y - y; + Type d = dx*dx+dy*dy; + return sqrt(d); + }; + + Type Distance2(Vector2d &a) // squared distance. + { + Type dx = a.x - x; + Type dy = a.y - y; + return dx*dx + dy *dy; + }; + + void Lerp(const Vector2d& from,const Vector2d& to,double slerp) + { + x = ((to.x - from.x)*slerp) + from.x; + y = ((to.y - from.y)*slerp) + from.y; + }; + + + void Cross(const Vector2d &a,const Vector2d &b) // cross two vectors result in this one. + { + x = a.y*b.x - a.x*b.y; + y = a.x*b.x - a.x*b.x; + }; + + Type Normalize(void) // normalize to a unit vector, returns distance. + { + Type l = Length(); + if ( l != 0 ) + { + l = Type( 1 ) / l; + x*=l; + y*=l; + } + else + { + x = y = 0; + } + return l; + }; + + Type FastNormalize(void) // normalize to a unit vector, returns distance. + { + Type l = FastLength(); + if ( l != 0 ) + { + l = Type( 1 ) / l; + x*=l; + y*=l; + } + else + { + x = y = 0; + } + return l; + }; + + Type FasterNormalize(void) // normalize to a unit vector, returns distance. + { + Type l = FasterLength(); + if ( l != 0 ) + { + l = Type( 1 ) / l; + x*=l; + y*=l; + } + else + { + x = y = 0; + } + return l; + }; + + + Type x; + Type y; +}; + +class Line +{ +public: + Line(const Vector3d &from,const Vector3d &to) + { + mP1 = from; + mP2 = to; + }; + // JWR Test for the intersection of two lines. + + bool Intersect(const Line& src,Vector3d §); +private: + Vector3d mP1; + Vector3d mP2; + +}; + + +typedef std::vector< Vector3d > Vector3dVector; +typedef std::vector< Vector2d > Vector2dVector; + +template Vector3d operator * (Type s, const Vector3d &v ) + { Vector3d Scaled(v.x*s, v.y*s, v.z*s); + return(Scaled); }; + +template Vector2d operator * (Type s, const Vector2d &v ) + { Vector2d Scaled(v.x*s, v.y*s); + return(Scaled); }; + +}; + +#endif diff --git a/convex_decomposition/ConvexDecomposition/ConvexDecomposition/cd_wavefront.cpp b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/cd_wavefront.cpp new file mode 100644 index 0000000..04b7b8c --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/cd_wavefront.cpp @@ -0,0 +1,858 @@ +#include +#include +#include +#include +#include + +#pragma warning(disable:4996) + +#include "cd_wavefront.h" + + +using namespace ConvexDecomposition; + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + + +#include + +namespace ConvexDecomposition +{ + +typedef std::vector< int > IntVector; +typedef std::vector< double > FloatVector; + +#if defined(__APPLE__) || defined(__CELLOS_LV2__) +#define stricmp(a, b) strcasecmp((a), (b)) +#endif + +/*******************************************************************/ +/******************** InParser.h ********************************/ +/*******************************************************************/ +class InPlaceParserInterface +{ +public: + virtual int ParseLine(int lineno,int argc,const char **argv) =0; // return TRUE to continue parsing, return FALSE to abort parsing process +}; + +enum SeparatorType +{ + ST_DATA, // is data + ST_HARD, // is a hard separator + ST_SOFT, // is a soft separator + ST_EOS // is a comment symbol, and everything past this character should be ignored +}; + +class InPlaceParser +{ +public: + InPlaceParser(void) + { + Init(); + } + + InPlaceParser(char *data,int len) + { + Init(); + SetSourceData(data,len); + } + + InPlaceParser(const char *fname) + { + Init(); + SetFile(fname); + } + + ~InPlaceParser(void); + + void Init(void) + { + mQuoteChar = 34; + mData = 0; + mLen = 0; + mMyAlloc = false; + for (int i=0; i<256; i++) + { + mHard[i] = ST_DATA; + mHardString[i*2] = i; + mHardString[i*2+1] = 0; + } + mHard[0] = ST_EOS; + mHard[32] = ST_SOFT; + mHard[9] = ST_SOFT; + mHard[13] = ST_SOFT; + mHard[10] = ST_SOFT; + } + + void SetFile(const char *fname); // use this file as source data to parse. + + void SetSourceData(char *data,int len) + { + mData = data; + mLen = len; + mMyAlloc = false; + }; + + int Parse(InPlaceParserInterface *callback); // returns true if entire file was parsed, false if it aborted for some reason + + int ProcessLine(int lineno,char *line,InPlaceParserInterface *callback); + + const char ** GetArglist(char *source,int &count); // convert source string into an arg list, this is a destructive parse. + + void SetHardSeparator(char c) // add a hard separator + { + mHard[c] = ST_HARD; + } + + void SetHard(char c) // add a hard separator + { + mHard[c] = ST_HARD; + } + + + void SetCommentSymbol(char c) // comment character, treated as 'end of string' + { + mHard[c] = ST_EOS; + } + + void ClearHardSeparator(char c) + { + mHard[c] = ST_DATA; + } + + + void DefaultSymbols(void); // set up default symbols for hard seperator and comment symbol of the '#' character. + + bool EOS(char c) + { + if ( mHard[c] == ST_EOS ) + { + return true; + } + return false; + } + + void SetQuoteChar(char c) + { + mQuoteChar = c; + } + +private: + + + inline char * AddHard(int &argc,const char **argv,char *foo); + inline bool IsHard(char c); + inline char * SkipSpaces(char *foo); + inline bool IsWhiteSpace(char c); + inline bool IsNonSeparator(char c); // non seperator,neither hard nor soft + + bool mMyAlloc; // whether or not *I* allocated the buffer and am responsible for deleting it. + char *mData; // ascii data to parse. + int mLen; // length of data + SeparatorType mHard[256]; + char mHardString[256*2]; + char mQuoteChar; +}; + +/*******************************************************************/ +/******************** InParser.cpp ********************************/ +/*******************************************************************/ +void InPlaceParser::SetFile(const char *fname) +{ + if ( mMyAlloc ) + { + free(mData); + } + mData = 0; + mLen = 0; + mMyAlloc = false; + + + FILE *fph = fopen(fname,"rb"); + if ( fph ) + { + fseek(fph,0L,SEEK_END); + mLen = ftell(fph); + fseek(fph,0L,SEEK_SET); + if ( mLen ) + { + mData = (char *) malloc(sizeof(char)*(mLen+1)); + int ok = fread(mData, mLen, 1, fph); + if ( !ok ) + { + free(mData); + mData = 0; + } + else + { + mData[mLen] = 0; // zero byte terminate end of file marker. + mMyAlloc = true; + } + } + fclose(fph); + } +} + +InPlaceParser::~InPlaceParser(void) +{ + if ( mMyAlloc ) + { + free(mData); + } +} + +#define MAXARGS 512 + +bool InPlaceParser::IsHard(char c) +{ + return mHard[c] == ST_HARD; +} + +char * InPlaceParser::AddHard(int &argc,const char **argv,char *foo) +{ + while ( IsHard(*foo) ) + { + const char *hard = &mHardString[*foo*2]; + if ( argc < MAXARGS ) + { + argv[argc++] = hard; + } + foo++; + } + return foo; +} + +bool InPlaceParser::IsWhiteSpace(char c) +{ + return mHard[c] == ST_SOFT; +} + +char * InPlaceParser::SkipSpaces(char *foo) +{ + while ( !EOS(*foo) && IsWhiteSpace(*foo) ) foo++; + return foo; +} + +bool InPlaceParser::IsNonSeparator(char c) +{ + if ( !IsHard(c) && !IsWhiteSpace(c) && c != 0 ) return true; + return false; +} + + +int InPlaceParser::ProcessLine(int lineno,char *line,InPlaceParserInterface *callback) +{ + int ret = 0; + + const char *argv[MAXARGS]; + int argc = 0; + + char *foo = line; + + while ( !EOS(*foo) && argc < MAXARGS ) + { + + foo = SkipSpaces(foo); // skip any leading spaces + + if ( EOS(*foo) ) break; + + if ( *foo == mQuoteChar ) // if it is an open quote + { + foo++; + if ( argc < MAXARGS ) + { + argv[argc++] = foo; + } + while ( !EOS(*foo) && *foo != mQuoteChar ) foo++; + if ( !EOS(*foo) ) + { + *foo = 0; // replace close quote with zero byte EOS + foo++; + } + } + else + { + + foo = AddHard(argc,argv,foo); // add any hard separators, skip any spaces + + if ( IsNonSeparator(*foo) ) // add non-hard argument. + { + bool quote = false; + if ( *foo == mQuoteChar ) + { + foo++; + quote = true; + } + + if ( argc < MAXARGS ) + { + argv[argc++] = foo; + } + + if ( quote ) + { + while (*foo && *foo != mQuoteChar ) foo++; + if ( *foo ) *foo = 32; + } + + // continue..until we hit an eos .. + while ( !EOS(*foo) ) // until we hit EOS + { + if ( IsWhiteSpace(*foo) ) // if we hit a space, stomp a zero byte, and exit + { + *foo = 0; + foo++; + break; + } + else if ( IsHard(*foo) ) // if we hit a hard separator, stomp a zero byte and store the hard separator argument + { + const char *hard = &mHardString[*foo*2]; + *foo = 0; + if ( argc < MAXARGS ) + { + argv[argc++] = hard; + } + foo++; + break; + } + foo++; + } // end of while loop... + } + } + } + + if ( argc ) + { + ret = callback->ParseLine(lineno, argc, argv ); + } + + return ret; +} + +int InPlaceParser::Parse(InPlaceParserInterface *callback) // returns true if entire file was parsed, false if it aborted for some reason +{ + assert( callback ); + if ( !mData ) return 0; + + int ret = 0; + + int lineno = 0; + + char *foo = mData; + char *begin = foo; + + + while ( *foo ) + { + if ( *foo == 10 || *foo == 13 ) + { + lineno++; + *foo = 0; + + if ( *begin ) // if there is any data to parse at all... + { + int v = ProcessLine(lineno,begin,callback); + if ( v ) ret = v; + } + + foo++; + if ( *foo == 10 ) foo++; // skip line feed, if it is in the carraige-return line-feed format... + begin = foo; + } + else + { + foo++; + } + } + + lineno++; // lasst line. + + int v = ProcessLine(lineno,begin,callback); + if ( v ) ret = v; + return ret; +} + + +void InPlaceParser::DefaultSymbols(void) +{ + SetHardSeparator(','); + SetHardSeparator('('); + SetHardSeparator(')'); + SetHardSeparator('='); + SetHardSeparator('['); + SetHardSeparator(']'); + SetHardSeparator('{'); + SetHardSeparator('}'); + SetCommentSymbol('#'); +} + + +const char ** InPlaceParser::GetArglist(char *line,int &count) // convert source string into an arg list, this is a destructive parse. +{ + const char **ret = 0; + + static const char *argv[MAXARGS]; + int argc = 0; + + char *foo = line; + + while ( !EOS(*foo) && argc < MAXARGS ) + { + + foo = SkipSpaces(foo); // skip any leading spaces + + if ( EOS(*foo) ) break; + + if ( *foo == mQuoteChar ) // if it is an open quote + { + foo++; + if ( argc < MAXARGS ) + { + argv[argc++] = foo; + } + while ( !EOS(*foo) && *foo != mQuoteChar ) foo++; + if ( !EOS(*foo) ) + { + *foo = 0; // replace close quote with zero byte EOS + foo++; + } + } + else + { + + foo = AddHard(argc,argv,foo); // add any hard separators, skip any spaces + + if ( IsNonSeparator(*foo) ) // add non-hard argument. + { + bool quote = false; + if ( *foo == mQuoteChar ) + { + foo++; + quote = true; + } + + if ( argc < MAXARGS ) + { + argv[argc++] = foo; + } + + if ( quote ) + { + while (*foo && *foo != mQuoteChar ) foo++; + if ( *foo ) *foo = 32; + } + + // continue..until we hit an eos .. + while ( !EOS(*foo) ) // until we hit EOS + { + if ( IsWhiteSpace(*foo) ) // if we hit a space, stomp a zero byte, and exit + { + *foo = 0; + foo++; + break; + } + else if ( IsHard(*foo) ) // if we hit a hard separator, stomp a zero byte and store the hard separator argument + { + const char *hard = &mHardString[*foo*2]; + *foo = 0; + if ( argc < MAXARGS ) + { + argv[argc++] = hard; + } + foo++; + break; + } + foo++; + } // end of while loop... + } + } + } + + count = argc; + if ( argc ) + { + ret = argv; + } + + return ret; +} + +/*******************************************************************/ +/******************** Geometry.h ********************************/ +/*******************************************************************/ + +class GeometryVertex +{ +public: + double mPos[3]; + double mNormal[3]; + double mTexel[2]; +}; + + +class GeometryInterface +{ +public: + + virtual void NodeTriangle(const GeometryVertex *v1,const GeometryVertex *v2,const GeometryVertex *v3) + { + } + +}; + + +/*******************************************************************/ +/******************** Obj.h ********************************/ +/*******************************************************************/ + + +class OBJ : public InPlaceParserInterface +{ +public: + int LoadMesh(const char *fname,GeometryInterface *callback); + int ParseLine(int lineno,int argc,const char **argv); // return TRUE to continue parsing, return FALSE to abort parsing process +private: + + void GetVertex(GeometryVertex &v,const char *face) const; + + FloatVector mVerts; + FloatVector mTexels; + FloatVector mNormals; + + GeometryInterface *mCallback; + friend class WavefrontObj; +}; + + +/*******************************************************************/ +/******************** Obj.cpp ********************************/ +/*******************************************************************/ + +int OBJ::LoadMesh(const char *fname,GeometryInterface *iface) +{ + int ret = 0; + + mVerts.clear(); + mTexels.clear(); + mNormals.clear(); + + mCallback = iface; + + InPlaceParser ipp(fname); + + ipp.Parse(this); + + + return ret; +} + +static const char * GetArg(const char **argv,int i,int argc) +{ + const char * ret = 0; + if ( i < argc ) ret = argv[i]; + return ret; +} + +void OBJ::GetVertex(GeometryVertex &v,const char *face) const +{ + v.mPos[0] = 0; + v.mPos[1] = 0; + v.mPos[2] = 0; + + v.mTexel[0] = 0; + v.mTexel[1] = 0; + + v.mNormal[0] = 0; + v.mNormal[1] = 1; + v.mNormal[2] = 0; + + int index = atoi( face )-1; + + const char *texel = strstr(face,"/"); + + if ( texel ) + { + int tindex = atoi( texel+1) - 1; + + if ( tindex >=0 && tindex < (int)(mTexels.size()/2) ) + { + const double *t = &mTexels[tindex*2]; + + v.mTexel[0] = t[0]; + v.mTexel[1] = t[1]; + + } + + const char *normal = strstr(texel+1,"/"); + if ( normal ) + { + int nindex = atoi( normal+1 ) - 1; + + if (nindex >= 0 && nindex < (int)(mNormals.size()/3) ) + { + const double *n = &mNormals[nindex*3]; + + v.mNormal[0] = n[0]; + v.mNormal[1] = n[1]; + v.mNormal[2] = n[2]; + } + } + } + + if ( index >= 0 && index < (int)(mVerts.size()/3) ) + { + + const double *p = &mVerts[index*3]; + + v.mPos[0] = p[0]; + v.mPos[1] = p[1]; + v.mPos[2] = p[2]; + } + +} + +int OBJ::ParseLine(int lineno,int argc,const char **argv) // return TRUE to continue parsing, return FALSE to abort parsing process +{ + int ret = 0; + + if ( argc >= 1 ) + { + const char *foo = argv[0]; + if ( *foo != '#' ) + { + if ( strcmp(argv[0],"v") == 0 && argc == 4 ) + { + double vx = (double) atof( argv[1] ); + double vy = (double) atof( argv[2] ); + double vz = (double) atof( argv[3] ); + mVerts.push_back(vx); + mVerts.push_back(vy); + mVerts.push_back(vz); + } + else if ( strcmp(argv[0],"vt") == 0 && argc == 3 ) + { + double tx = (double) atof( argv[1] ); + double ty = (double) atof( argv[2] ); + mTexels.push_back(tx); + mTexels.push_back(ty); + } + else if ( strcmp(argv[0],"vn") == 0 && argc == 4 ) + { + double normalx = (double) atof(argv[1]); + double normaly = (double) atof(argv[2]); + double normalz = (double) atof(argv[3]); + mNormals.push_back(normalx); + mNormals.push_back(normaly); + mNormals.push_back(normalz); + } + else if ( strcmp(argv[0],"f") == 0 && argc >= 4 ) + { + GeometryVertex v[32]; + + int vcount = argc-1; + + for (int i=1; i p1( v[0].mPos ); + Vector3d p2( v[1].mPos ); + Vector3d p3( v[2].mPos ); + + Vector3d n; + n.ComputeNormal(p3,p2,p1); + + for (int i=0; iNodeTriangle(&v[0],&v[1],&v[2]); + + if ( vcount >=3 ) // do the fan + { + for (int i=2; i<(vcount-1); i++) + { + mCallback->NodeTriangle(&v[0],&v[i],&v[i+1]); + } + } + + } + } + } + + return ret; +} + + + + +class BuildMesh : public GeometryInterface +{ +public: + + int GetIndex(const double *p) + { + + int vcount = mVertices.size()/3; + + if(vcount>0) + { + //New MS STL library checks indices in debug build, so zero causes an assert if it is empty. + const double *v = &mVertices[0]; + + for (int i=0; imPos) ); + mIndices.push_back( GetIndex(v2->mPos) ); + mIndices.push_back( GetIndex(v3->mPos) ); + } + + const FloatVector& GetVertices(void) const { return mVertices; }; + const IntVector& GetIndices(void) const { return mIndices; }; + +private: + FloatVector mVertices; + IntVector mIndices; +}; + + +WavefrontObj::WavefrontObj(void) +{ + mVertexCount = 0; + mTriCount = 0; + mIndices = 0; + mVertices = 0; +} + +WavefrontObj::~WavefrontObj(void) +{ + delete mIndices; + delete mVertices; +} + +unsigned int WavefrontObj::loadObj(const char *fname) // load a wavefront obj returns number of triangles that were loaded. Data is persists until the class is destructed. +{ + + unsigned int ret = 0; + + delete mVertices; + mVertices = 0; + delete mIndices; + mIndices = 0; + mVertexCount = 0; + mTriCount = 0; + + + BuildMesh bm; + + OBJ obj; + + obj.LoadMesh(fname,&bm); + + + const FloatVector &vlist = bm.GetVertices(); + const IntVector &indices = bm.GetIndices(); + if ( vlist.size() ) + { + mVertexCount = vlist.size()/3; + mVertices = new double[mVertexCount*3]; + memcpy( mVertices, &vlist[0], sizeof(double)*mVertexCount*3 ); + mTriCount = indices.size()/3; + mIndices = new int[mTriCount*3*sizeof(int)]; + memcpy(mIndices, &indices[0], sizeof(int)*mTriCount*3); + ret = mTriCount; + } + else if( obj.mVerts.size() > 0 ) { + // take consecutive vertices + mVertexCount = obj.mVerts.size()/3; + mVertices = new double[mVertexCount*3]; + memcpy( mVertices, &obj.mVerts[0], sizeof(double)*mVertexCount*3 ); + mTriCount = mVertexCount/3; + mIndices = new int[mTriCount*3*sizeof(int)]; + for(int i = 0; i < mVertexCount; ++i) + mIndices[i] = i; + ret = mTriCount; + } + + return ret; +} + +}; diff --git a/convex_decomposition/ConvexDecomposition/ConvexDecomposition/cd_wavefront.h b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/cd_wavefront.h new file mode 100644 index 0000000..4eff55c --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/cd_wavefront.h @@ -0,0 +1,82 @@ +#ifndef CD_WAVEFRONT_OBJ_H + + +#define CD_WAVEFRONT_OBJ_H + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + + +namespace ConvexDecomposition +{ + +class WavefrontObj +{ +public: + + WavefrontObj(void); + ~WavefrontObj(void); + + unsigned int loadObj(const char *fname); // load a wavefront obj returns number of triangles that were loaded. Data is persists until the class is destructed. + + int mVertexCount; + int mTriCount; + int *mIndices; + double *mVertices; +}; + +}; + +#endif diff --git a/convex_decomposition/ConvexDecomposition/ConvexDecomposition/concavity.cpp b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/concavity.cpp new file mode 100644 index 0000000..77cbd7b --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/concavity.cpp @@ -0,0 +1,821 @@ +#include +#include +#include +#include + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + + +#include + +#include "concavity.h" +#include "raytri.h" +#include "bestfit.h" +#include "cd_hull.h" +#include "meshvolume.h" +#include "cd_vector.h" +#include "splitplane.h" +#include "ConvexDecomposition.h" + + +#define WSCALE 4 +#define CONCAVE_THRESH 0.05f + +namespace ConvexDecomposition +{ + +unsigned int getDebugColor(void) +{ + static unsigned int colors[8] = + { + 0xFF0000, + 0x00FF00, + 0x0000FF, + 0xFFFF00, + 0x00FFFF, + 0xFF00FF, + 0xFFFFFF, + 0xFF8040 + }; + + static int count = 0; + + count++; + + if ( count == 8 ) count = 0; + + assert( count >= 0 && count < 8 ); + + unsigned int color = colors[count]; + + return color; + +} + +class Wpoint +{ +public: + Wpoint(const Vector3d &p,double w) + { + mPoint = p; + mWeight = w; + } + + Vector3d mPoint; + double mWeight; +}; + +typedef std::vector< Wpoint > WpointVector; + + +static inline double DistToPt(const double *p,const double *plane) +{ + double x = p[0]; + double y = p[1]; + double z = p[2]; + double d = x*plane[0] + y*plane[1] + z*plane[2] + plane[3]; + return d; +} + + +static void intersect(const double *p1,const double *p2,double *split,const double *plane) +{ + + double dp1 = DistToPt(p1,plane); + double dp2 = DistToPt(p2,plane); + + double dir[3]; + + dir[0] = p2[0] - p1[0]; + dir[1] = p2[1] - p1[1]; + dir[2] = p2[2] - p1[2]; + + double dot1 = dir[0]*plane[0] + dir[1]*plane[1] + dir[2]*plane[2]; + double dot2 = dp1 - plane[3]; + + double t = -(plane[3] + dot2 ) / dot1; + + split[0] = (dir[0]*t)+p1[0]; + split[1] = (dir[1]*t)+p1[1]; + split[2] = (dir[2]*t)+p1[2]; + +} + + +class CTri +{ +public: + CTri(void) { }; + + CTri(const double *p1,const double *p2,const double *p3,unsigned int i1,unsigned int i2,unsigned int i3) + { + mProcessed = 0; + mI1 = i1; + mI2 = i2; + mI3 = i3; + + mP1.Set(p1); + mP2.Set(p2); + mP3.Set(p3); + + mPlaneD = mNormal.ComputePlane(mP1,mP2,mP3); + } + + double Facing(const CTri &t) + { + double d = mNormal.Dot(t.mNormal); + return d; + } + + // clip this line segment against this triangle. + bool clip(const Vector3d &start,Vector3d &end) const + { + Vector3d sect; + + bool hit = lineIntersectsTriangle(start.Ptr(), end.Ptr(), mP1.Ptr(), mP2.Ptr(), mP3.Ptr(), sect.Ptr() ); + + if ( hit ) + { + end = sect; + } + return hit; + } + + bool Concave(const Vector3d &p,double &distance,Vector3d &n) const + { + n.NearestPointInTriangle(p,mP1,mP2,mP3); + distance = p.Distance(n); + return true; + } + + void addTri(unsigned int *indices,unsigned int i1,unsigned int i2,unsigned int i3,unsigned int &tcount) const + { + indices[tcount*3+0] = i1; + indices[tcount*3+1] = i2; + indices[tcount*3+2] = i3; + tcount++; + } + + double getVolume(ConvexDecompInterface *callback) const + { + unsigned int indices[8*3]; + + + unsigned int tcount = 0; + + addTri(indices,0,1,2,tcount); + addTri(indices,3,4,5,tcount); + + addTri(indices,0,3,4,tcount); + addTri(indices,0,4,1,tcount); + + addTri(indices,1,4,5,tcount); + addTri(indices,1,5,2,tcount); + + addTri(indices,0,3,5,tcount); + addTri(indices,0,5,2,tcount); + + const double *vertices = mP1.Ptr(); + + if ( callback ) + { + unsigned int color = getDebugColor(); + +#if 0 + Vector3d d1 = mNear1; + Vector3d d2 = mNear2; + Vector3d d3 = mNear3; + + callback->ConvexDebugPoint(mP1.Ptr(),0.01f,0x00FF00); + callback->ConvexDebugPoint(mP2.Ptr(),0.01f,0x00FF00); + callback->ConvexDebugPoint(mP3.Ptr(),0.01f,0x00FF00); + callback->ConvexDebugPoint(d1.Ptr(),0.01f,0xFF0000); + callback->ConvexDebugPoint(d2.Ptr(),0.01f,0xFF0000); + callback->ConvexDebugPoint(d3.Ptr(),0.01f,0xFF0000); + + callback->ConvexDebugTri(mP1.Ptr(), d1.Ptr(), d1.Ptr(),0x00FF00); + callback->ConvexDebugTri(mP2.Ptr(), d2.Ptr(), d2.Ptr(),0x00FF00); + callback->ConvexDebugTri(mP3.Ptr(), d3.Ptr(), d3.Ptr(),0x00FF00); + +#else + for (unsigned int i=0; iConvexDebugTri(p1,p2,p3,color); + + } +#endif + } + + double v = computeMeshVolume(mP1.Ptr(), tcount, indices ); + + return v; + + } + + double raySect(const Vector3d &p,const Vector3d &dir,Vector3d §) const + { + double plane[4]; + + plane[0] = mNormal.x; + plane[1] = mNormal.y; + plane[2] = mNormal.z; + plane[3] = mPlaneD; + + Vector3d dest = p+dir*100000; + + intersect( p.Ptr(), dest.Ptr(), sect.Ptr(), plane ); + + return sect.Distance(p); // return the intersection distance. + + } + + double planeDistance(const Vector3d &p) const + { + double plane[4]; + + plane[0] = mNormal.x; + plane[1] = mNormal.y; + plane[2] = mNormal.z; + plane[3] = mPlaneD; + + return DistToPt( p.Ptr(), plane ); + + } + + bool samePlane(const CTri &t) const + { + const double THRESH = 0.001f; + double dd = fabs( t.mPlaneD - mPlaneD ); + if ( dd > THRESH ) return false; + dd = fabs( t.mNormal.x - mNormal.x ); + if ( dd > THRESH ) return false; + dd = fabs( t.mNormal.y - mNormal.y ); + if ( dd > THRESH ) return false; + dd = fabs( t.mNormal.z - mNormal.z ); + if ( dd > THRESH ) return false; + return true; + } + + bool hasIndex(unsigned int i) const + { + if ( i == mI1 || i == mI2 || i == mI3 ) return true; + return false; + } + + bool sharesEdge(const CTri &t) const + { + bool ret = false; + unsigned int count = 0; + + if ( t.hasIndex(mI1) ) count++; + if ( t.hasIndex(mI2) ) count++; + if ( t.hasIndex(mI3) ) count++; + + if ( count >= 2 ) ret = true; + + return ret; + } + + void debug(unsigned int color,ConvexDecompInterface *callback) + { + callback->ConvexDebugTri( mP1.Ptr(), mP2.Ptr(), mP3.Ptr(), color ); + callback->ConvexDebugTri( mP1.Ptr(), mP1.Ptr(), mNear1.Ptr(), 0xFF0000 ); + callback->ConvexDebugTri( mP2.Ptr(), mP2.Ptr(), mNear2.Ptr(), 0xFF0000 ); + callback->ConvexDebugTri( mP2.Ptr(), mP3.Ptr(), mNear3.Ptr(), 0xFF0000 ); + callback->ConvexDebugPoint( mNear1.Ptr(), 0.01f, 0xFF0000 ); + callback->ConvexDebugPoint( mNear2.Ptr(), 0.01f, 0xFF0000 ); + callback->ConvexDebugPoint( mNear3.Ptr(), 0.01f, 0xFF0000 ); + } + + double area(void) + { + double a = mConcavity*mP1.Area(mP2,mP3); + return a; + } + + void addWeighted(WpointVector &list,ConvexDecompInterface *callback) + { + + Wpoint p1(mP1,mC1); + Wpoint p2(mP2,mC2); + Wpoint p3(mP3,mC3); + + Vector3d d1 = mNear1 - mP1; + Vector3d d2 = mNear2 - mP2; + Vector3d d3 = mNear3 - mP3; + + d1*=WSCALE; + d2*=WSCALE; + d3*=WSCALE; + + d1 = d1 + mP1; + d2 = d2 + mP2; + d3 = d3 + mP3; + + Wpoint p4(d1,mC1); + Wpoint p5(d2,mC2); + Wpoint p6(d3,mC3); + + list.push_back(p1); + list.push_back(p2); + list.push_back(p3); + + list.push_back(p4); + list.push_back(p5); + list.push_back(p6); + +#if 0 + callback->ConvexDebugPoint(mP1.Ptr(),0.01f,0x00FF00); + callback->ConvexDebugPoint(mP2.Ptr(),0.01f,0x00FF00); + callback->ConvexDebugPoint(mP3.Ptr(),0.01f,0x00FF00); + callback->ConvexDebugPoint(d1.Ptr(),0.01f,0xFF0000); + callback->ConvexDebugPoint(d2.Ptr(),0.01f,0xFF0000); + callback->ConvexDebugPoint(d3.Ptr(),0.01f,0xFF0000); + + callback->ConvexDebugTri(mP1.Ptr(), d1.Ptr(), d1.Ptr(),0x00FF00); + callback->ConvexDebugTri(mP2.Ptr(), d2.Ptr(), d2.Ptr(),0x00FF00); + callback->ConvexDebugTri(mP3.Ptr(), d3.Ptr(), d3.Ptr(),0x00FF00); + + Vector3d np1 = mP1 + mNormal*0.05f; + Vector3d np2 = mP2 + mNormal*0.05f; + Vector3d np3 = mP3 + mNormal*0.05f; + + callback->ConvexDebugTri(mP1.Ptr(), np1.Ptr(), np1.Ptr(), 0xFF00FF ); + callback->ConvexDebugTri(mP2.Ptr(), np2.Ptr(), np2.Ptr(), 0xFF00FF ); + callback->ConvexDebugTri(mP3.Ptr(), np3.Ptr(), np3.Ptr(), 0xFF00FF ); + + callback->ConvexDebugPoint( np1.Ptr(), 0.01F, 0XFF00FF ); + callback->ConvexDebugPoint( np2.Ptr(), 0.01F, 0XFF00FF ); + callback->ConvexDebugPoint( np3.Ptr(), 0.01F, 0XFF00FF ); + +#endif + + + + } + + Vector3d mP1; + Vector3d mP2; + Vector3d mP3; + Vector3d mNear1; + Vector3d mNear2; + Vector3d mNear3; + Vector3d mNormal; + double mPlaneD; + double mConcavity; + double mC1; + double mC2; + double mC3; + unsigned int mI1; + unsigned int mI2; + unsigned int mI3; + int mProcessed; // already been added... +}; + +typedef std::vector< CTri > CTriVector; + +bool featureMatch(CTri &m,const CTriVector &tris,ConvexDecompInterface *callback,const CTriVector &input_mesh) +{ + + bool ret = false; + + double neardot = 0.707f; + + m.mConcavity = 0; + + //gLog->Display("*********** FEATURE MATCH *************\r\n"); + //gLog->Display("Plane: %0.4f,%0.4f,%0.4f %0.4f\r\n", m.mNormal.x, m.mNormal.y, m.mNormal.z, m.mPlaneD ); + //gLog->Display("*********************************************\r\n"); + + CTriVector::const_iterator i; + + CTri nearest; + + double near[3] = { 1e9, 1e9, 1e9 }; + + for (i=tris.begin(); i!=tris.end(); ++i) + { + const CTri &t = (*i); + + + //gLog->Display(" HullPlane: %0.4f,%0.4f,%0.4f %0.4f\r\n", t.mNormal.x, t.mNormal.y, t.mNormal.z, t.mPlaneD ); + + if ( t.samePlane(m) ) + { + //gLog->Display("*** PLANE MATCH!!!\r\n"); + ret = false; + break; + } + + double dot = t.mNormal.Dot(m.mNormal); + + if ( dot > neardot ) + { + + double d1 = t.planeDistance( m.mP1 ); + double d2 = t.planeDistance( m.mP2 ); + double d3 = t.planeDistance( m.mP3 ); + + if ( d1 > 0.001f || d2 > 0.001f || d3 > 0.001f ) // can't be near coplaner! + { + + neardot = dot; + + Vector3d n1,n2,n3; + + t.raySect( m.mP1, m.mNormal, m.mNear1 ); + t.raySect( m.mP2, m.mNormal, m.mNear2 ); + t.raySect( m.mP3, m.mNormal, m.mNear3 ); + + nearest = t; + + ret = true; + } + + } + } + + if ( ret ) + { + if ( 0 ) + { + CTriVector::const_iterator i; + for (i=input_mesh.begin(); i!=input_mesh.end(); ++i) + { + const CTri &c = (*i); + if ( c.mI1 != m.mI1 && c.mI2 != m.mI2 && c.mI3 != m.mI3 ) + { + c.clip( m.mP1, m.mNear1 ); + c.clip( m.mP2, m.mNear2 ); + c.clip( m.mP3, m.mNear3 ); + } + } + } + + //gLog->Display("*********************************************\r\n"); + //gLog->Display(" HullPlaneNearest: %0.4f,%0.4f,%0.4f %0.4f\r\n", nearest.mNormal.x, nearest.mNormal.y, nearest.mNormal.z, nearest.mPlaneD ); + + m.mC1 = m.mP1.Distance( m.mNear1 ); + m.mC2 = m.mP2.Distance( m.mNear2 ); + m.mC3 = m.mP3.Distance( m.mNear3 ); + + m.mConcavity = m.mC1; + + if ( m.mC2 > m.mConcavity ) m.mConcavity = m.mC2; + if ( m.mC3 > m.mConcavity ) m.mConcavity = m.mC3; + + #if 0 + callback->ConvexDebugTri( m.mP1.Ptr(), m.mP2.Ptr(), m.mP3.Ptr(), 0x00FF00 ); + callback->ConvexDebugTri( m.mNear1.Ptr(), m.mNear2.Ptr(), m.mNear3.Ptr(), 0xFF0000 ); + + callback->ConvexDebugTri( m.mP1.Ptr(), m.mP1.Ptr(), m.mNear1.Ptr(), 0xFFFF00 ); + callback->ConvexDebugTri( m.mP2.Ptr(), m.mP2.Ptr(), m.mNear2.Ptr(), 0xFFFF00 ); + callback->ConvexDebugTri( m.mP3.Ptr(), m.mP3.Ptr(), m.mNear3.Ptr(), 0xFFFF00 ); + #endif + + } + else + { + //gLog->Display("No match\r\n"); + } + + //gLog->Display("*********************************************\r\n"); + return ret; +} + +bool isFeatureTri(CTri &t,CTriVector &flist,double fc,ConvexDecompInterface *callback,unsigned int color) +{ + bool ret = false; + + if ( t.mProcessed == 0 ) // if not already processed + { + + double c = t.mConcavity / fc; // must be within 80% of the concavity of the parent. + + if ( c > 0.85f ) + { + // see if this triangle is a 'feature' triangle. Meaning it shares an + // edge with any existing feature triangle and is within roughly the same + // concavity of the parent. + if ( flist.size() ) + { + CTriVector::iterator i; + for (i=flist.begin(); i!=flist.end(); ++i) + { + CTri &ftri = (*i); + if ( ftri.sharesEdge(t) ) + { + t.mProcessed = 2; // it is now part of a feature. + flist.push_back(t); // add it to the feature list. +// callback->ConvexDebugTri( t.mP1.Ptr(), t.mP2.Ptr(),t.mP3.Ptr(), color ); + ret = true; + break; + } + } + } + else + { + t.mProcessed = 2; + flist.push_back(t); // add it to the feature list. +// callback->ConvexDebugTri( t.mP1.Ptr(), t.mP2.Ptr(),t.mP3.Ptr(), color ); + ret = true; + } + } + else + { + t.mProcessed = 1; // eliminated for this feature, but might be valid for the next one.. + } + + } + return ret; +} + +double computeConcavity(unsigned int vcount, + const double *vertices, + unsigned int tcount, + const unsigned int *indices, + ConvexDecompInterface *callback, + double *plane, // plane equation to split on + double &volume) +{ + + + double cret = 0; + volume = 1; + + HullResult result; + HullLibrary hl; + HullDesc desc; + + desc.mMaxVertices = 256; + desc.SetHullFlag(QF_TRIANGLES); + + + desc.mVcount = vcount; + desc.mVertices = vertices; + desc.mVertexStride = sizeof(double)*3; + + HullError ret = hl.CreateConvexHull(desc,result); + + if ( ret == QE_OK ) + { + + double bmin[3]; + double bmax[3]; + + double diagonal = getBoundingRegion( result.mNumOutputVertices, result.mOutputVertices, sizeof(double)*3, bmin, bmax ); + + double dx = bmax[0] - bmin[0]; + double dy = bmax[1] - bmin[1]; + double dz = bmax[2] - bmin[2]; + + Vector3d center; + + center.x = bmin[0] + dx*0.5f; + center.y = bmin[1] + dy*0.5f; + center.z = bmin[2] + dz*0.5f; + + double boundVolume = dx*dy*dz; + + volume = computeMeshVolume2( result.mOutputVertices, result.mNumFaces, result.mIndices ); + +#if 1 + // ok..now..for each triangle on the original mesh.. + // we extrude the points to the nearest point on the hull. + const unsigned int *source = result.mIndices; + + CTriVector tris; + + for (unsigned int i=0; iConvexDebugTri(p1,p2,p3,0xFFFFFF); + + CTri t(p1,p2,p3,i1,i2,i3); // + tris.push_back(t); + } + + // we have not pre-computed the plane equation for each triangle in the convex hull.. + + double totalVolume = 0; + + CTriVector ftris; // 'feature' triangles. + + const unsigned int *src = indices; + + + double maxc=0; + + + if ( 1 ) + { + CTriVector input_mesh; + if ( 1 ) + { + const unsigned int *src = indices; + for (unsigned int i=0; i CONCAVE_THRESH ) + { + + if ( t.mConcavity > maxc ) + { + maxc = t.mConcavity; + maxctri = t; + } + + double v = t.getVolume(0); + totalVolume+=v; + ftris.push_back(t); + } + + } + } + + if ( ftris.size() && 0 ) + { + + // ok..now we extract the triangles which form the maximum concavity. + CTriVector major_feature; + double maxarea = 0; + + while ( maxc > CONCAVE_THRESH ) + { + + unsigned int color = getDebugColor(); // + + CTriVector flist; + + bool found; + + double totalarea = 0; + + do + { + found = false; + CTriVector::iterator i; + for (i=ftris.begin(); i!=ftris.end(); ++i) + { + CTri &t = (*i); + if ( isFeatureTri(t,flist,maxc,callback,color) ) + { + found = true; + totalarea+=t.area(); + } + } + } while ( found ); + + + if ( totalarea > maxarea ) + { + major_feature = flist; + maxarea = totalarea; + } + + maxc = 0; + + for (unsigned int i=0; i maxc ) + { + maxc = t.mConcavity; + } + } + } + } + + unsigned int color = getDebugColor(); + + WpointVector list; + for (unsigned int i=0; i +#include +#include +#include +#include + +#include "fitsphere.h" + + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + + + +/* +An Efficient Bounding Sphere +by Jack Ritter +from "Graphics Gems", Academic Press, 1990 +*/ + +/* Routine to calculate tight bounding sphere over */ +/* a set of points in 3D */ +/* This contains the routine find_bounding_sphere(), */ +/* the struct definition, and the globals used for parameters. */ +/* The abs() of all coordinates must be < BIGNUMBER */ +/* Code written by Jack Ritter and Lyle Rains. */ + +namespace ConvexDecomposition +{ + +#define BIGNUMBER 100000000.0 /* hundred million */ + +static inline void Set(double *n,double x,double y,double z) +{ + n[0] = x; + n[1] = y; + n[2] = z; +}; + +static inline void Copy(double *dest,const double *source) +{ + dest[0] = source[0]; + dest[1] = source[1]; + dest[2] = source[2]; +} + +double computeBoundingSphere(unsigned int vcount,const double *points,double *center) +{ + + double mRadius; + double mRadius2; + + double xmin[3]; + double xmax[3]; + double ymin[3]; + double ymax[3]; + double zmin[3]; + double zmax[3]; + double dia1[3]; + double dia2[3]; + + /* FIRST PASS: find 6 minima/maxima points */ + Set(xmin,BIGNUMBER,BIGNUMBER,BIGNUMBER); + Set(xmax,-BIGNUMBER,-BIGNUMBER,-BIGNUMBER); + Set(ymin,BIGNUMBER,BIGNUMBER,BIGNUMBER); + Set(ymax,-BIGNUMBER,-BIGNUMBER,-BIGNUMBER); + Set(zmin,BIGNUMBER,BIGNUMBER,BIGNUMBER); + Set(zmax,-BIGNUMBER,-BIGNUMBER,-BIGNUMBER); + + for (unsigned i=0; ixmax[0]) + Copy(xmax,caller_p); + if (caller_p[1]ymax[1]) + Copy(ymax,caller_p); + if (caller_p[2]zmax[2]) + Copy(zmax,caller_p); + } + + /* Set xspan = distance between the 2 points xmin & xmax (squared) */ + double dx = xmax[0] - xmin[0]; + double dy = xmax[1] - xmin[1]; + double dz = xmax[2] - xmin[2]; + double xspan = dx*dx + dy*dy + dz*dz; + + /* Same for y & z spans */ + dx = ymax[0] - ymin[0]; + dy = ymax[1] - ymin[1]; + dz = ymax[2] - ymin[2]; + double yspan = dx*dx + dy*dy + dz*dz; + + dx = zmax[0] - zmin[0]; + dy = zmax[1] - zmin[1]; + dz = zmax[2] - zmin[2]; + double zspan = dx*dx + dy*dy + dz*dz; + + /* Set points dia1 & dia2 to the maximally separated pair */ + Copy(dia1,xmin); + Copy(dia2,xmax); /* assume xspan biggest */ + double maxspan = xspan; + + if (yspan>maxspan) + { + maxspan = yspan; + Copy(dia1,ymin); + Copy(dia2,ymax); + } + + if (zspan>maxspan) + { + Copy(dia1,zmin); + Copy(dia2,zmax); + } + + + /* dia1,dia2 is a diameter of initial sphere */ + /* calc initial center */ + center[0] = (dia1[0]+dia2[0])*0.5f; + center[1] = (dia1[1]+dia2[1])*0.5f; + center[2] = (dia1[2]+dia2[2])*0.5f; + + /* calculate initial radius**2 and radius */ + + dx = dia2[0]-center[0]; /* x component of radius vector */ + dy = dia2[1]-center[1]; /* y component of radius vector */ + dz = dia2[2]-center[2]; /* z component of radius vector */ + + mRadius2 = dx*dx + dy*dy + dz*dz; + mRadius = double(sqrt(mRadius2)); + + /* SECOND PASS: increment current sphere */ + if ( 1 ) + { + for (unsigned i=0; i mRadius2) /* do r**2 test first */ + { /* this point is outside of current sphere */ + double old_to_p = double(sqrt(old_to_p_sq)); + /* calc radius of new sphere */ + mRadius = (mRadius + old_to_p) * 0.5f; + mRadius2 = mRadius*mRadius; /* for next r**2 compare */ + double old_to_new = old_to_p - mRadius; + + /* calc center of new sphere */ + + double recip = 1.0f /old_to_p; + + double cx = (mRadius*center[0] + old_to_new*caller_p[0]) * recip; + double cy = (mRadius*center[1] + old_to_new*caller_p[1]) * recip; + double cz = (mRadius*center[2] + old_to_new*caller_p[2]) * recip; + + Set(center,cx,cy,cz); + } + } + } + + return mRadius; +} + +static inline void Set(float *n,float x,float y,float z) +{ + n[0] = x; + n[1] = y; + n[2] = z; +}; + +static inline void Copy(float *dest,const float *source) +{ + dest[0] = source[0]; + dest[1] = source[1]; + dest[2] = source[2]; +} + + + +float computeBoundingSphere(unsigned int vcount,const float *points,float *center) +{ + float mRadius; + float mRadius2; + + float xmin[3]; + float xmax[3]; + float ymin[3]; + float ymax[3]; + float zmin[3]; + float zmax[3]; + float dia1[3]; + float dia2[3]; + + /* FIRST PASS: find 6 minima/maxima points */ + Set(xmin,BIGNUMBER,BIGNUMBER,BIGNUMBER); + Set(xmax,-BIGNUMBER,-BIGNUMBER,-BIGNUMBER); + Set(ymin,BIGNUMBER,BIGNUMBER,BIGNUMBER); + Set(ymax,-BIGNUMBER,-BIGNUMBER,-BIGNUMBER); + Set(zmin,BIGNUMBER,BIGNUMBER,BIGNUMBER); + Set(zmax,-BIGNUMBER,-BIGNUMBER,-BIGNUMBER); + + for (unsigned i=0; ixmax[0]) + Copy(xmax,caller_p); + if (caller_p[1]ymax[1]) + Copy(ymax,caller_p); + if (caller_p[2]zmax[2]) + Copy(zmax,caller_p); + } + + /* Set xspan = distance between the 2 points xmin & xmax (squared) */ + float dx = xmax[0] - xmin[0]; + float dy = xmax[1] - xmin[1]; + float dz = xmax[2] - xmin[2]; + float xspan = dx*dx + dy*dy + dz*dz; + + /* Same for y & z spans */ + dx = ymax[0] - ymin[0]; + dy = ymax[1] - ymin[1]; + dz = ymax[2] - ymin[2]; + float yspan = dx*dx + dy*dy + dz*dz; + + dx = zmax[0] - zmin[0]; + dy = zmax[1] - zmin[1]; + dz = zmax[2] - zmin[2]; + float zspan = dx*dx + dy*dy + dz*dz; + + /* Set points dia1 & dia2 to the maximally separated pair */ + Copy(dia1,xmin); + Copy(dia2,xmax); /* assume xspan biggest */ + float maxspan = xspan; + + if (yspan>maxspan) + { + maxspan = yspan; + Copy(dia1,ymin); + Copy(dia2,ymax); + } + + if (zspan>maxspan) + { + Copy(dia1,zmin); + Copy(dia2,zmax); + } + + + /* dia1,dia2 is a diameter of initial sphere */ + /* calc initial center */ + center[0] = (dia1[0]+dia2[0])*0.5f; + center[1] = (dia1[1]+dia2[1])*0.5f; + center[2] = (dia1[2]+dia2[2])*0.5f; + + /* calculate initial radius**2 and radius */ + + dx = dia2[0]-center[0]; /* x component of radius vector */ + dy = dia2[1]-center[1]; /* y component of radius vector */ + dz = dia2[2]-center[2]; /* z component of radius vector */ + + mRadius2 = dx*dx + dy*dy + dz*dz; + mRadius = float(sqrt(mRadius2)); + + /* SECOND PASS: increment current sphere */ + if ( 1 ) + { + for (unsigned i=0; i mRadius2) /* do r**2 test first */ + { /* this point is outside of current sphere */ + float old_to_p = float(sqrt(old_to_p_sq)); + /* calc radius of new sphere */ + mRadius = (mRadius + old_to_p) * 0.5f; + mRadius2 = mRadius*mRadius; /* for next r**2 compare */ + float old_to_new = old_to_p - mRadius; + + /* calc center of new sphere */ + + float recip = 1.0f /old_to_p; + + float cx = (mRadius*center[0] + old_to_new*caller_p[0]) * recip; + float cy = (mRadius*center[1] + old_to_new*caller_p[1]) * recip; + float cz = (mRadius*center[2] + old_to_new*caller_p[2]) * recip; + + Set(center,cx,cy,cz); + } + } + } + + return mRadius; +} + + +double computeSphereVolume(double r) +{ + return (4.0f*3.141592654f*r*r*r)/3.0f; // 4/3 PI R cubed +} + +}; diff --git a/convex_decomposition/ConvexDecomposition/ConvexDecomposition/fitsphere.h b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/fitsphere.h new file mode 100644 index 0000000..200310f --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/fitsphere.h @@ -0,0 +1,70 @@ +#ifndef FIT_SPHERE_H + +#define FIT_SPHERE_H + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + +namespace ConvexDecomposition +{ + +double computeBoundingSphere(unsigned int vcount,const double *points,double *center); +float computeBoundingSphere(unsigned int vcount,const float *points,float *center); + +double computeSphereVolume(double r); + +}; + +#endif diff --git a/convex_decomposition/ConvexDecomposition/ConvexDecomposition/float_math.cpp b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/float_math.cpp new file mode 100644 index 0000000..8c106fe --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/float_math.cpp @@ -0,0 +1,463 @@ +#include +#include +#include +#include +#include + +#include "float_math.h" + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + + +// a set of routines that let you do common 3d math +// operations without any vector, matrix, or quaternion +// classes or templates. +// +// a vector (or point) is a 'double *' to 3 doubleing point numbers. +// a matrix is a 'double *' to an array of 16 doubleing point numbers representing a 4x4 transformation matrix compatible with D3D or OGL +// a quaternion is a 'double *' to 4 doubles representing a quaternion x,y,z,w +// +// +// +// Please email bug fixes or improvements to John W. Ratcliff at mailto:jratcliff@infiniplex.net +// +// If you find this source code useful donate a couple of bucks to my kid's fund raising website at +// www.amillionpixels.us +// +// More snippets at: www.codesuppository.com +// + +namespace ConvexDecomposition +{ + +void fm_inverseRT(const double *matrix,const double *pos,double *t) // inverse rotate translate the point. +{ + + double _x = pos[0] - matrix[3*4+0]; + double _y = pos[1] - matrix[3*4+1]; + double _z = pos[2] - matrix[3*4+2]; + + // Multiply inverse-translated source vector by inverted rotation transform + + t[0] = (matrix[0*4+0] * _x) + (matrix[0*4+1] * _y) + (matrix[0*4+2] * _z); + t[1] = (matrix[1*4+0] * _x) + (matrix[1*4+1] * _y) + (matrix[1*4+2] * _z); + t[2] = (matrix[2*4+0] * _x) + (matrix[2*4+1] * _y) + (matrix[2*4+2] * _z); + +} + + +void fm_identity(double *matrix) // set 4x4 matrix to identity. +{ + matrix[0*4+0] = 1; + matrix[1*4+1] = 1; + matrix[2*4+2] = 1; + matrix[3*4+3] = 1; + + matrix[1*4+0] = 0; + matrix[2*4+0] = 0; + matrix[3*4+0] = 0; + + matrix[0*4+1] = 0; + matrix[2*4+1] = 0; + matrix[3*4+1] = 0; + + matrix[0*4+2] = 0; + matrix[1*4+2] = 0; + matrix[3*4+2] = 0; + + matrix[0*4+3] = 0; + matrix[1*4+3] = 0; + matrix[2*4+3] = 0; + +} + +void fm_eulerMatrix(double ax,double ay,double az,double *matrix) // convert euler (in radians) to a dest 4x4 matrix (translation set to zero) +{ + double quat[4]; + fm_eulerToQuat(ax,ay,az,quat); + fm_quatToMatrix(quat,matrix); +} + +void fm_getAABB(unsigned int vcount,const double *points,unsigned int pstride,double *bmin,double *bmax) +{ + + const unsigned char *source = (const unsigned char *) points; + + bmin[0] = points[0]; + bmin[1] = points[1]; + bmin[2] = points[2]; + + bmax[0] = points[0]; + bmax[1] = points[1]; + bmax[2] = points[2]; + + + for (unsigned int i=1; i bmax[0] ) bmax[0] = p[0]; + if ( p[1] > bmax[1] ) bmax[1] = p[1]; + if ( p[2] > bmax[2] ) bmax[2] = p[2]; + + } +} + + +void fm_eulerToQuat(double roll,double pitch,double yaw,double *quat) // convert euler angles to quaternion. +{ + roll *= 0.5f; + pitch *= 0.5f; + yaw *= 0.5f; + + double cr = cos(roll); + double cp = cos(pitch); + double cy = cos(yaw); + + double sr = sin(roll); + double sp = sin(pitch); + double sy = sin(yaw); + + double cpcy = cp * cy; + double spsy = sp * sy; + double spcy = sp * cy; + double cpsy = cp * sy; + + quat[0] = ( sr * cpcy - cr * spsy); + quat[1] = ( cr * spcy + sr * cpsy); + quat[2] = ( cr * cpsy - sr * spcy); + quat[3] = cr * cpcy + sr * spsy; +} + +void fm_quatToMatrix(const double *quat,double *matrix) // convert quaterinion rotation to matrix, zeros out the translation component. +{ + + double xx = quat[0]*quat[0]; + double yy = quat[1]*quat[1]; + double zz = quat[2]*quat[2]; + double xy = quat[0]*quat[1]; + double xz = quat[0]*quat[2]; + double yz = quat[1]*quat[2]; + double wx = quat[3]*quat[0]; + double wy = quat[3]*quat[1]; + double wz = quat[3]*quat[2]; + + matrix[0*4+0] = 1 - 2 * ( yy + zz ); + matrix[1*4+0] = 2 * ( xy - wz ); + matrix[2*4+0] = 2 * ( xz + wy ); + + matrix[0*4+1] = 2 * ( xy + wz ); + matrix[1*4+1] = 1 - 2 * ( xx + zz ); + matrix[2*4+1] = 2 * ( yz - wx ); + + matrix[0*4+2] = 2 * ( xz - wy ); + matrix[1*4+2] = 2 * ( yz + wx ); + matrix[2*4+2] = 1 - 2 * ( xx + yy ); + + matrix[3*4+0] = 0.0f; + matrix[3*4+1] = 0.0f; + matrix[3*4+2] = 0.0f; + + matrix[0*4+3] = 0.0f; + matrix[1*4+3] = 0.0f; + matrix[2*4+3] = 0.0f; + + matrix[3*4+3] =(double) 1.0f; + +} + + +void fm_quatRotate(const double *quat,const double *v,double *r) // rotate a vector directly by a quaternion. +{ + double left[4]; + + left[0] = quat[3]*v[0] + quat[1]*v[2] - v[1]*quat[2]; + left[1] = quat[3]*v[1] + quat[2]*v[0] - v[2]*quat[0]; + left[2] = quat[3]*v[2] + quat[0]*v[1] - v[0]*quat[1]; + left[3] = - quat[0]*v[0] - quat[1]*v[1] - quat[2]*v[2]; + + r[0] = (left[3]*-quat[0]) + (quat[3]*left[0]) + (left[1]*-quat[2]) - (-quat[1]*left[2]); + r[1] = (left[3]*-quat[1]) + (quat[3]*left[1]) + (left[2]*-quat[0]) - (-quat[2]*left[0]); + r[2] = (left[3]*-quat[2]) + (quat[3]*left[2]) + (left[0]*-quat[1]) - (-quat[0]*left[1]); + +} + + +void fm_getTranslation(const double *matrix,double *t) +{ + t[0] = matrix[3*4+0]; + t[1] = matrix[3*4+1]; + t[2] = matrix[3*4+2]; +} + +void fm_matrixToQuat(const double *matrix,double *quat) // convert the 3x3 portion of a 4x4 matrix into a quaterion as x,y,z,w +{ + + double tr = matrix[0*4+0] + matrix[1*4+1] + matrix[2*4+2]; + + // check the diagonal + + if (tr > 0.0f ) + { + double s = (double) sqrt ( (double) (tr + 1.0f) ); + quat[3] = s * 0.5f; + s = 0.5f / s; + quat[0] = (matrix[1*4+2] - matrix[2*4+1]) * s; + quat[1] = (matrix[2*4+0] - matrix[0*4+2]) * s; + quat[2] = (matrix[0*4+1] - matrix[1*4+0]) * s; + + } + else + { + // diagonal is negative + int nxt[3] = {1, 2, 0}; + double qa[4]; + + int i = 0; + + if (matrix[1*4+1] > matrix[0*4+0]) i = 1; + if (matrix[2*4+2] > matrix[i*4+i]) i = 2; + + int j = nxt[i]; + int k = nxt[j]; + + double s = sqrt ( ((matrix[i*4+i] - (matrix[j*4+j] + matrix[k*4+k])) + 1.0f) ); + + qa[i] = s * 0.5f; + + if (s != 0.0f ) s = 0.5f / s; + + qa[3] = (matrix[j*4+k] - matrix[k*4+j]) * s; + qa[j] = (matrix[i*4+j] + matrix[j*4+i]) * s; + qa[k] = (matrix[i*4+k] + matrix[k*4+i]) * s; + + quat[0] = qa[0]; + quat[1] = qa[1]; + quat[2] = qa[2]; + quat[3] = qa[3]; + } + + +} + + +double fm_sphereVolume(double radius) // return's the volume of a sphere of this radius (4/3 PI * R cubed ) +{ + return (4.0f / 3.0f ) * FM_PI * radius * radius * radius; +} + + +double fm_cylinderVolume(double radius,double h) +{ + return FM_PI * radius * radius *h; +} + +double fm_capsuleVolume(double radius,double h) +{ + double volume = fm_sphereVolume(radius); // volume of the sphere portion. + double ch = h-radius*2; // this is the cylinder length + if ( ch > 0 ) + { + volume+=fm_cylinderVolume(radius,ch); + } + return volume; +} + +void fm_transform(const double *matrix,const double *v,double *t) // rotate and translate this point +{ + t[0] = (matrix[0*4+0] * v[0]) + (matrix[1*4+0] * v[1]) + (matrix[2*4+0] * v[2]) + matrix[3*4+0]; + t[1] = (matrix[0*4+1] * v[0]) + (matrix[1*4+1] * v[1]) + (matrix[2*4+1] * v[2]) + matrix[3*4+1]; + t[2] = (matrix[0*4+2] * v[0]) + (matrix[1*4+2] * v[1]) + (matrix[2*4+2] * v[2]) + matrix[3*4+2]; +} + +void fm_rotate(const double *matrix,const double *v,double *t) // rotate and translate this point +{ + t[0] = (matrix[0*4+0] * v[0]) + (matrix[1*4+0] * v[1]) + (matrix[2*4+0] * v[2]); + t[1] = (matrix[0*4+1] * v[0]) + (matrix[1*4+1] * v[1]) + (matrix[2*4+1] * v[2]); + t[2] = (matrix[0*4+2] * v[0]) + (matrix[1*4+2] * v[1]) + (matrix[2*4+2] * v[2]); +} + + +double fm_distance(const double *p1,const double *p2) +{ + double dx = p1[0] - p2[0]; + double dy = p1[1] - p2[1]; + double dz = p1[2] - p2[2]; + + return sqrt( dx*dx + dy*dy + dz *dz ); +} + +double fm_distanceSquared(const double *p1,const double *p2) +{ + double dx = p1[0] - p2[0]; + double dy = p1[1] - p2[1]; + double dz = p1[2] - p2[2]; + + return dx*dx + dy*dy + dz *dz; +} + + +double fm_computePlane(const double *A,const double *B,const double *C,double *n) // returns D +{ + double vx = (B[0] - C[0]); + double vy = (B[1] - C[1]); + double vz = (B[2] - C[2]); + + double wx = (A[0] - B[0]); + double wy = (A[1] - B[1]); + double wz = (A[2] - B[2]); + + double vw_x = vy * wz - vz * wy; + double vw_y = vz * wx - vx * wz; + double vw_z = vx * wy - vy * wx; + + double mag = sqrt((vw_x * vw_x) + (vw_y * vw_y) + (vw_z * vw_z)); + + if ( mag < 0.000001f ) + { + mag = 0; + } + else + { + mag = 1.0f/mag; + } + + double x = vw_x * mag; + double y = vw_y * mag; + double z = vw_z * mag; + + + double D = 0.0f - ((x*A[0])+(y*A[1])+(z*A[2])); + + n[0] = x; + n[1] = y; + n[2] = z; + + return D; +} + +double fm_distToPlane(const double *plane,const double *p) // computes the distance of this point from the plane. +{ + return p[0]*plane[0]+p[1]*plane[1]+p[2]*plane[2]+plane[3]; +} + +double fm_dot(const double *p1,const double *p2) +{ + return p1[0]*p2[0]+p1[1]*p2[2]+p1[2]*p2[2]; +} + +void fm_cross(double *cross,const double *a,const double *b) +{ + cross[0] = a[1]*b[2] - a[2]*b[1]; + cross[1] = a[2]*b[0] - a[0]*b[2]; + cross[2] = a[0]*b[1] - a[1]*b[0]; +} + +void fm_computeNormalVector(double *n,const double *p1,const double *p2) +{ + n[0] = p2[0] - p1[0]; + n[1] = p2[1] - p1[1]; + n[2] = p2[2] - p1[2]; + fm_normalize(n); +} + +bool fm_computeWindingOrder(const double *p1,const double *p2,const double *p3) // returns true if the triangle is clockwise. +{ + bool ret = false; + + double v1[3]; + double v2[3]; + + fm_computeNormalVector(v1,p1,p2); // p2-p1 (as vector) and then normalized + fm_computeNormalVector(v2,p1,p3); // p3-p1 (as vector) and then normalized + + double cross[3]; + + fm_cross(cross, v1, v2 ); + double ref[3] = { 1, 0, 0 }; + + double d = fm_dot( cross, ref ); + + + if ( d <= 0 ) + ret = false; + else + ret = true; + + return ret; +} + +void fm_normalize(double *n) // normalize this vector +{ + + double dist = n[0]*n[0] + n[1]*n[1] + n[2]*n[2]; + double mag = 0; + + if ( dist > 0.0000001f ) + mag = 1.0f / sqrt(dist); + + n[0]*=mag; + n[1]*=mag; + n[2]*=mag; + +} + +}; // end of namespace diff --git a/convex_decomposition/ConvexDecomposition/ConvexDecomposition/float_math.h b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/float_math.h new file mode 100644 index 0000000..b819b8d --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/float_math.h @@ -0,0 +1,112 @@ +#ifndef FLOAT_MATH_H + +#define FLOAT_MATH_H + +namespace ConvexDecomposition +{ + + /*! + ** + ** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net + ** + ** Portions of this source has been released with the PhysXViewer application, as well as + ** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. + ** + ** If you find this code useful or you are feeling particularily generous I would + ** ask that you please go to http://www.amillionpixels.us and make a donation + ** to Troy DeMolay. + ** + ** DeMolay is a youth group for young men between the ages of 12 and 21. + ** It teaches strong moral principles, as well as leadership skills and + ** public speaking. The donations page uses the 'pay for pixels' paradigm + ** where, in this case, a pixel is only a single penny. Donations can be + ** made for as small as $4 or as high as a $100 block. Each person who donates + ** will get a link to their own site as well as acknowledgement on the + ** donations blog located here http://www.amillionpixels.blogspot.com/ + ** + ** If you wish to contact me you can use the following methods: + ** + ** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) + ** Skype ID: jratcliff63367 + ** Yahoo: jratcliff63367 + ** AOL: jratcliff1961 + ** email: jratcliff@infiniplex.net + ** Personal website: http://jratcliffscarab.blogspot.com + ** Coding Website: http://codesuppository.blogspot.com + ** FundRaising Blog: http://amillionpixels.blogspot.com + ** Fundraising site: http://www.amillionpixels.us + ** New Temple Site: http://newtemple.blogspot.com + ** + ** + ** The MIT license: + ** + ** Permission is hereby granted, free of charge, to any person obtaining a copy + ** of this software and associated documentation files (the "Software"), to deal + ** in the Software without restriction, including without limitation the rights + ** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + ** copies of the Software, and to permit persons to whom the Software is furnished + ** to do so, subject to the following conditions: + ** + ** The above copyright notice and this permission notice shall be included in all + ** copies or substantial portions of the Software. + + ** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + ** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + ** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + ** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, + ** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + ** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + + */ + + + +// a set of routines that let you do common 3d math +// operations without any vector, matrix, or quaternion +// classes or templates. +// +// a vector (or point) is a 'double *' to 3 doubleing point numbers. +// a matrix is a 'double *' to an array of 16 doubleing point numbers representing a 4x4 transformation matrix compatible with D3D or OGL +// a quaternion is a 'double *' to 4 doubles representing a quaternion x,y,z,w +// +// +// +// Please email bug fixes or improvements to John W. Ratcliff at mailto:jratcliff@infiniplex.net +// +// If you find this source code useful donate a couple of bucks to my kid's fund raising website at +// www.amillionpixels.us +// +// More snippets at: www.codesuppository.com +// + +const double FM_PI = 3.141592654f; +const double FM_DEG_TO_RAD = ((2.0f * FM_PI) / 360.0f); +const double FM_RAD_TO_DEG = (360.0f / (2.0f * FM_PI)); + +void fm_identity(double *matrix); // set 4x4 matrix to identity. +void fm_inverseRT(const double *matrix,const double *pos,double *t); // inverse rotate translate the point. +void fm_transform(const double *matrix,const double *pos,double *t); // rotate and translate this point. +void fm_rotate(const double *matrix,const double *pos,double *t); // only rotate the point by a 4x4 matrix, don't translate. +void fm_eulerMatrix(double ax,double ay,double az,double *matrix); // convert euler (in radians) to a dest 4x4 matrix (translation set to zero) +void fm_getAABB(unsigned int vcount,const double *points,unsigned int pstride,double *bmin,double *bmax); +void fm_eulerToQuat(double roll,double pitch,double yaw,double *quat); // convert euler angles to quaternion. +void fm_quatToMatrix(const double *quat,double *matrix); // convert quaterinion rotation to matrix, translation set to zero. +void fm_quatRotate(const double *quat,const double *v,double *r); // rotate a vector directly by a quaternion. +void fm_getTranslation(const double *matrix,double *t); +void fm_matrixToQuat(const double *matrix,double *quat); // convert the 3x3 portion of a 4x4 matrix into a quaterion as x,y,z,w +double fm_sphereVolume(double radius); // return's the volume of a sphere of this radius (4/3 PI * R cubed ) +double fm_cylinderVolume(double radius,double h); +double fm_capsuleVolume(double radius,double h); +double fm_distance(const double *p1,const double *p2); +double fm_distanceSquared(const double *p1,const double *p2); +double fm_computePlane(const double *p1,const double *p2,const double *p3,double *n); // return D +double fm_distToPlane(const double *plane,const double *pos); // computes the distance of this point from the plane. +double fm_dot(const double *p1,const double *p2); +void fm_cross(double *cross,const double *a,const double *b); +void fm_computeNormalVector(double *n,const double *p1,const double *p2); // as P2-P1 normalized. +bool fm_computeWindingOrder(const double *p1,const double *p2,const double *p3); // returns true if the triangle is clockwise. +void fm_normalize(double *n); // normalize this vector + +}; // end of nsamepace + +#endif diff --git a/convex_decomposition/ConvexDecomposition/ConvexDecomposition/meshvolume.cpp b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/meshvolume.cpp new file mode 100644 index 0000000..453dada --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/meshvolume.cpp @@ -0,0 +1,251 @@ +#include "meshvolume.h" + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + +namespace ConvexDecomposition +{ + + +inline double det(const double *p1,const double *p2,const double *p3) +{ + return p1[0]*p2[1]*p3[2] + p2[0]*p3[1]*p1[2] + p3[0]*p1[1]*p2[2] -p1[0]*p3[1]*p2[2] - p2[0]*p1[1]*p3[2] - p3[0]*p2[1]*p1[2]; +} + +double computeMeshVolume(const double *vertices,unsigned int tcount,const unsigned int *indices) +{ + double volume = 0; + + const double *p0 = vertices; + for (unsigned int i=0; i +#include +#include +#include + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + + +#include "planetri.h" + +namespace ConvexDecomposition +{ + + +static inline double DistToPt(const double *p,const double *plane) +{ + double x = p[0]; + double y = p[1]; + double z = p[2]; + double d = x*plane[0] + y*plane[1] + z*plane[2] + plane[3]; + return d; +} + + +static PlaneTriResult getSidePlane(const double *p,const double *plane,double epsilon) +{ + + double d = DistToPt(p,plane); + + if ( (d+epsilon) > 0 ) + return PTR_FRONT; // it is 'in front' within the provided epsilon value. + + return PTR_BACK; +} + +static void add(const double *p,double *dest,unsigned int tstride,unsigned int &pcount) +{ + char *d = (char *) dest; + d = d + pcount*tstride; + dest = (double *) d; + dest[0] = p[0]; + dest[1] = p[1]; + dest[2] = p[2]; + pcount++; + assert( pcount <= 4 ); +} + + +// assumes that the points are on opposite sides of the plane! +static void intersect(const double *p1,const double *p2,double *split,const double *plane) +{ + + double dp1 = DistToPt(p1,plane); + double dp2 = DistToPt(p2,plane); + + double dir[3]; + + dir[0] = p2[0] - p1[0]; + dir[1] = p2[1] - p1[1]; + dir[2] = p2[2] - p1[2]; + + double dot1 = dir[0]*plane[0] + dir[1]*plane[1] + dir[2]*plane[2]; + double dot2 = dp1 - plane[3]; + + double t = -(plane[3] + dot2 ) / dot1; + + split[0] = (dir[0]*t)+p1[0]; + split[1] = (dir[1]*t)+p1[1]; + split[2] = (dir[2]*t)+p1[2]; + +} + +#define MAXPTS 256 + +class point +{ +public: + + void set(const double *p) + { + x = p[0]; + y = p[1]; + z = p[2]; + } + + double x; + double y; + double z; +}; +class polygon +{ +public: + polygon(void) + { + mVcount = 0; + } + + polygon(const double *p1,const double *p2,const double *p3) + { + mVcount = 3; + mVertices[0].set(p1); + mVertices[1].set(p2); + mVertices[2].set(p3); + } + + + int NumVertices(void) const { return mVcount; }; + + const point& Vertex(int index) + { + if ( index < 0 ) index+=mVcount; + return mVertices[index]; + }; + + + void set(const point *pts,int count) + { + for (int i=0; iNumVertices (); + int out_c = 0, in_c = 0; + point ptA, ptB,outpts[MAXPTS],inpts[MAXPTS]; + double sideA, sideB; + ptA = poly->Vertex (count - 1); + sideA = part->Classify_Point (ptA); + for (int i = -1; ++i < count;) + { + ptB = poly->Vertex(i); + sideB = part->Classify_Point(ptB); + if (sideB > 0) + { + if (sideA < 0) + { + point v; + intersect(&ptB.x, &ptA.x, &v.x, &part->normal.x ); + outpts[out_c++] = inpts[in_c++] = v; + } + outpts[out_c++] = ptB; + } + else if (sideB < 0) + { + if (sideA > 0) + { + point v; + intersect(&ptB.x, &ptA.x, &v.x, &part->normal.x ); + outpts[out_c++] = inpts[in_c++] = v; + } + inpts[in_c++] = ptB; + } + else + outpts[out_c++] = inpts[in_c++] = ptB; + ptA = ptB; + sideA = sideB; + } + + front.set(&outpts[0], out_c); + back.set(&inpts[0], in_c); +} + +PlaneTriResult planeTriIntersection(const double *_plane, // the plane equation in Ax+By+Cz+D format + const double *triangle, // the source triangle. + unsigned int tstride, // stride in bytes of the input and output *vertices* + double epsilon, // the co-planer epsilon value. + double *front, // the triangle in front of the + unsigned int &fcount, // number of vertices in the 'front' triangle + double *back, // the triangle in back of the plane + unsigned int &bcount) // the number of vertices in the 'back' triangle. +{ + + fcount = 0; + bcount = 0; + + const char *tsource = (const char *) triangle; + + // get the three vertices of the triangle. + const double *p1 = (const double *) (tsource); + const double *p2 = (const double *) (tsource+tstride); + const double *p3 = (const double *) (tsource+tstride*2); + + + PlaneTriResult r1 = getSidePlane(p1,_plane,epsilon); // compute the side of the plane each vertex is on + PlaneTriResult r2 = getSidePlane(p2,_plane,epsilon); + PlaneTriResult r3 = getSidePlane(p3,_plane,epsilon); + + if ( r1 == r2 && r1 == r3 ) // if all three vertices are on the same side of the plane. + { + if ( r1 == PTR_FRONT ) // if all three are in front of the plane, then copy to the 'front' output triangle. + { + add(p1,front,tstride,fcount); + add(p2,front,tstride,fcount); + add(p3,front,tstride,fcount); + } + else + { + add(p1,back,tstride,bcount); // if all three are in 'back' then copy to the 'back' output triangle. + add(p2,back,tstride,bcount); + add(p3,back,tstride,bcount); + } + return r1; // if all three points are on the same side of the plane return result + } + + + polygon pi(p1,p2,p3); + polygon pfront,pback; + + plane part(_plane); + Split_Polygon(&pi,&part,pfront,pback); + + for (int i=0; i +#include +#include +#include +#include + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + + +#include "raytri.h" + +namespace ConvexDecomposition +{ + + +/* a = b - c */ +#define vector(a,b,c) \ + (a)[0] = (b)[0] - (c)[0]; \ + (a)[1] = (b)[1] - (c)[1]; \ + (a)[2] = (b)[2] - (c)[2]; + + + +#define innerProduct(v,q) \ + ((v)[0] * (q)[0] + \ + (v)[1] * (q)[1] + \ + (v)[2] * (q)[2]) + +#define crossProduct(a,b,c) \ + (a)[0] = (b)[1] * (c)[2] - (c)[1] * (b)[2]; \ + (a)[1] = (b)[2] * (c)[0] - (c)[2] * (b)[0]; \ + (a)[2] = (b)[0] * (c)[1] - (c)[0] * (b)[1]; + +bool rayIntersectsTriangle(const double *p,const double *d,const double *v0,const double *v1,const double *v2,double &t) +{ + + double e1[3],e2[3],h[3],s[3],q[3]; + double a,f,u,v; + + vector(e1,v1,v0); + vector(e2,v2,v0); + crossProduct(h,d,e2); + a = innerProduct(e1,h); + + if (a > -0.00001 && a < 0.00001) + return(false); + + f = 1/a; + vector(s,p,v0); + u = f * (innerProduct(s,h)); + + if (u < 0.0 || u > 1.0) + return(false); + + crossProduct(q,s,e1); + v = f * innerProduct(d,q); + if (v < 0.0 || u + v > 1.0) + return(false); + // at this stage we can compute t to find out where + // the intersection point is on the line + t = f * innerProduct(e2,q); + if (t > 0) // ray intersection + return(true); + else // this means that there is a line intersection + // but not a ray intersection + return (false); +} + + +bool lineIntersectsTriangle(const double *rayStart,const double *rayEnd,const double *p1,const double *p2,const double *p3,double *sect) +{ + double dir[3]; + + dir[0] = rayEnd[0] - rayStart[0]; + dir[1] = rayEnd[1] - rayStart[1]; + dir[2] = rayEnd[2] - rayStart[2]; + + double d = sqrt(dir[0]*dir[0] + dir[1]*dir[1] + dir[2]*dir[2]); + double r = 1.0f / d; + + dir[0]*=r; + dir[1]*=r; + dir[2]*=r; + + + double t; + + bool ret = rayIntersectsTriangle(rayStart, dir, p1, p2, p3, t ); + + if ( ret ) + { + if ( t > d ) + { + sect[0] = rayStart[0] + dir[0]*t; + sect[1] = rayStart[1] + dir[1]*t; + sect[2] = rayStart[2] + dir[2]*t; + } + else + { + ret = false; + } + } + + return ret; +} + +}; // end of namespace diff --git a/convex_decomposition/ConvexDecomposition/ConvexDecomposition/raytri.h b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/raytri.h new file mode 100644 index 0000000..647a658 --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/raytri.h @@ -0,0 +1,69 @@ +#ifndef RAY_TRI_H + +#define RAY_TRI_H + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + +namespace ConvexDecomposition +{ + +// returns true if the ray intersects the triangle. +bool lineIntersectsTriangle(const double *rayStart,const double *rayEnd,const double *p1,const double *p2,const double *p3,double *sect); +bool rayIntersectsTriangle(const double *p,const double *d,const double *v0,const double *v1,const double *v2,double &t); + +}; + +#endif diff --git a/convex_decomposition/ConvexDecomposition/ConvexDecomposition/splitplane.cpp b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/splitplane.cpp new file mode 100644 index 0000000..154cead --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/splitplane.cpp @@ -0,0 +1,339 @@ +#include +#include +#include +#include +#include +#include + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + + +#include "splitplane.h" +#include "ConvexDecomposition.h" +#include "cd_vector.h" +#include "cd_hull.h" +#include "cd_wavefront.h" +#include "bestfit.h" +#include "planetri.h" +#include "vlookup.h" +#include "meshvolume.h" +#include "bestfitobb.h" +#include "float_math.h" + +namespace ConvexDecomposition +{ + +static void computePlane(const double *A,const double *B,const double *C,double *plane) +{ + + double vx = (B[0] - C[0]); + double vy = (B[1] - C[1]); + double vz = (B[2] - C[2]); + + double wx = (A[0] - B[0]); + double wy = (A[1] - B[1]); + double wz = (A[2] - B[2]); + + double vw_x = vy * wz - vz * wy; + double vw_y = vz * wx - vx * wz; + double vw_z = vx * wy - vy * wx; + + double mag = sqrt((vw_x * vw_x) + (vw_y * vw_y) + (vw_z * vw_z)); + + if ( mag < 0.000001f ) + { + mag = 0; + } + else + { + mag = 1.0f/mag; + } + + double x = vw_x * mag; + double y = vw_y * mag; + double z = vw_z * mag; + + + double D = 0.0f - ((x*A[0])+(y*A[1])+(z*A[2])); + + plane[0] = x; + plane[1] = y; + plane[2] = z; + plane[3] = D; + +} + +class Rect3d +{ +public: + Rect3d(void) { }; + + Rect3d(const double *bmin,const double *bmax) + { + + mMin[0] = bmin[0]; + mMin[1] = bmin[1]; + mMin[2] = bmin[2]; + + mMax[0] = bmax[0]; + mMax[1] = bmax[1]; + mMax[2] = bmax[2]; + + } + + void SetMin(const double *bmin) + { + mMin[0] = bmin[0]; + mMin[1] = bmin[1]; + mMin[2] = bmin[2]; + } + + void SetMax(const double *bmax) + { + mMax[0] = bmax[0]; + mMax[1] = bmax[1]; + mMax[2] = bmax[2]; + } + + void SetMin(double x,double y,double z) + { + mMin[0] = x; + mMin[1] = y; + mMin[2] = z; + } + + void SetMax(double x,double y,double z) + { + mMax[0] = x; + mMax[1] = y; + mMax[2] = z; + } + + double mMin[3]; + double mMax[3]; +}; + +void splitRect(unsigned int axis, + const Rect3d &source, + Rect3d &b1, + Rect3d &b2, + const double *midpoint) +{ + switch ( axis ) + { + case 0: + b1.SetMin(source.mMin); + b1.SetMax( midpoint[0], source.mMax[1], source.mMax[2] ); + + b2.SetMin( midpoint[0], source.mMin[1], source.mMin[2] ); + b2.SetMax(source.mMax); + + break; + case 1: + b1.SetMin(source.mMin); + b1.SetMax( source.mMax[0], midpoint[1], source.mMax[2] ); + + b2.SetMin( source.mMin[0], midpoint[1], source.mMin[2] ); + b2.SetMax(source.mMax); + + break; + case 2: + b1.SetMin(source.mMin); + b1.SetMax( source.mMax[0], source.mMax[1], midpoint[2] ); + + b2.SetMin( source.mMin[0], source.mMin[1], midpoint[2] ); + b2.SetMax(source.mMax); + + break; + } +} + +bool computeSplitPlane(unsigned int vcount, + const double *vertices, + unsigned int tcount, + const unsigned int *indices, + ConvexDecompInterface *callback, + double *plane) +{ + bool cret = false; + + + double sides[3]; + double matrix[16]; + + computeBestFitOBB( vcount, vertices, sizeof(double)*3, sides, matrix ); + + double bmax[3]; + double bmin[3]; + + bmax[0] = sides[0]*0.5f; + bmax[1] = sides[1]*0.5f; + bmax[2] = sides[2]*0.5f; + + bmin[0] = -bmax[0]; + bmin[1] = -bmax[1]; + bmin[2] = -bmax[2]; + + + double dx = sides[0]; + double dy = sides[1]; + double dz = sides[2]; + + + double laxis = dx; + + unsigned int axis = 0; + + if ( dy > dx ) + { + axis = 1; + laxis = dy; + } + + if ( dz > dx && dz > dy ) + { + axis = 2; + laxis = dz; + } + + double p1[3]; + double p2[3]; + double p3[3]; + + p3[0] = p2[0] = p1[0] = bmin[0] + dx*0.5f; + p3[1] = p2[1] = p1[1] = bmin[1] + dy*0.5f; + p3[2] = p2[2] = p1[2] = bmin[2] + dz*0.5f; + + Rect3d b(bmin,bmax); + + Rect3d b1,b2; + + splitRect(axis,b,b1,b2,p1); + + +// callback->ConvexDebugBound(b1.mMin,b1.mMax,0x00FF00); +// callback->ConvexDebugBound(b2.mMin,b2.mMax,0xFFFF00); + + switch ( axis ) + { + case 0: + p2[1] = bmin[1]; + p2[2] = bmin[2]; + + if ( dz > dy ) + { + p3[1] = bmax[1]; + p3[2] = bmin[2]; + } + else + { + p3[1] = bmin[1]; + p3[2] = bmax[2]; + } + + break; + case 1: + p2[0] = bmin[0]; + p2[2] = bmin[2]; + + if ( dx > dz ) + { + p3[0] = bmax[0]; + p3[2] = bmin[2]; + } + else + { + p3[0] = bmin[0]; + p3[2] = bmax[2]; + } + + break; + case 2: + p2[0] = bmin[0]; + p2[1] = bmin[1]; + + if ( dx > dy ) + { + p3[0] = bmax[0]; + p3[1] = bmin[1]; + } + else + { + p3[0] = bmin[0]; + p3[1] = bmax[1]; + } + + break; + } + + double tp1[3]; + double tp2[3]; + double tp3[3]; + + fm_transform(matrix,p1,tp1); + fm_transform(matrix,p2,tp2); + fm_transform(matrix,p3,tp3); + +// callback->ConvexDebugTri(p1,p2,p3,0xFF0000); + + computePlane(tp1,tp2,tp3,plane); + + return true; + +} + + +}; diff --git a/convex_decomposition/ConvexDecomposition/ConvexDecomposition/splitplane.h b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/splitplane.h new file mode 100644 index 0000000..e7869dd --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/splitplane.h @@ -0,0 +1,76 @@ +#ifndef SPLIT_PLANE_H + +#define SPLIT_PLANE_H + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + + +namespace ConvexDecomposition +{ + +class ConvexDecompInterface; + +bool computeSplitPlane(unsigned int vcount, + const double *vertices, + unsigned int tcount, + const unsigned int *indices, + ConvexDecompInterface *callback, + double *plane); + + +}; + +#endif diff --git a/convex_decomposition/ConvexDecomposition/ConvexDecomposition/triangulate.cpp b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/triangulate.cpp new file mode 100644 index 0000000..03b517b --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/triangulate.cpp @@ -0,0 +1,410 @@ +#include +#include +#include +#include +#include + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + + +#include // Include STL vector class. + +#include "triangulate.h" + + +namespace ConvexDecomposition +{ + + +class Vec2d +{ +public: + Vec2d(const double *v) + { + mX = v[0]; + mY = v[1]; + } + Vec2d(double x,double y) + { + Set(x,y); + }; + double GetX(void) const { return mX; }; + double GetY(void) const { return mY; }; + + void Set(double x,double y) + { + mX = x; + mY = y; + }; + +private: + double mX; + double mY; +};// Typedef an STL vector of vertices which are used to represent +// a polygon/contour and a series of triangles. + +typedef std::vector< Vec2d > Vec2dVector; + +static bool Process(const Vec2dVector &contour,Vec2dVector &result); // compute area of a contour/polygon +static double Area(const Vec2dVector &contour); // decide if point Px/Py is inside triangle defined by (Ax,Ay) (Bx,By) (Cx,Cy) +static bool InsideTriangle(double Ax, double Ay,double Bx, double By,double Cx, double Cy,double Px, double Py); +static bool Snip(const Vec2dVector &contour,int u,int v,int w,int n,int *V); + +static const double EPSILON=0.0000000001f; + +double Area(const Vec2dVector &contour) +{ + int n = contour.size(); + double A=0.0f; + for(int p=n-1,q=0; q= 0.0f) && (bCROSScp >= 0.0f) && (cCROSSap >= 0.0f)); +}; + +bool Snip(const Vec2dVector &contour,int u,int v,int w,int n,int *V) +{ + int p; + double Ax, Ay, Bx, By, Cx, Cy, Px, Py; + Ax = contour[V[u]].GetX(); + Ay = contour[V[u]].GetY(); + Bx = contour[V[v]].GetX(); + By = contour[V[v]].GetY(); + Cx = contour[V[w]].GetX(); + Cy = contour[V[w]].GetY(); + if ( EPSILON > (((Bx-Ax)*(Cy-Ay)) - ((By-Ay)*(Cx-Ax))) ) return false; for (p=0;p2; ) + { + /* if we loop, it is probably a non-simple polygon */ + if (0 >= (count--)) + { + //** Triangulate: ERROR - probable bad polygon! + return false; + } /* three consecutive vertices in current polygon, */ + + int u = v ; + if (nv <= u) u = 0; /* previous */ + v = u+1; if (nv <= v) v = 0; /* new v */ + int w = v+1; + if (nv <= w) w = 0; /* next */ + + if ( Snip(contour,u,v,w,nv,V) ) + { + int a,b,c,s,t; /* true names of the vertices */ + + a = V[u]; + b = V[v]; + c = V[w]; /* output Triangle */ + + result.push_back( contour[a] ); + result.push_back( contour[b] ); + result.push_back( contour[c] ); + + m++; /* remove v from remaining polygon */ + for(s=v,t=v+1;t= 3 ) + { + double normal[3]; + + normal[0] = plane[0]; + normal[1] = plane[1]; + normal[2] = plane[2]; + double D = plane[3]; + + unsigned int i0 = 0; + unsigned int i1 = 1; + unsigned int i2 = 2; + unsigned int axis = 0; + + + // find the dominant axis. + double dx = fabs(normal[0]); + double dy = fabs(normal[1]); + double dz = fabs(normal[2]); + + if ( dx > dy && dx > dz ) + { + axis = 0; + i0 = 1; + i1 = 2; + i2 = 0; + } + else if ( dy > dx && dy > dz ) + { + i0 = 0; + i1 = 2; + i2 = 1; + axis = 1; + } + else if ( dz > dx && dz > dy ) + { + i0 = 0; + i1 = 1; + i2 = 2; + axis = 2; + } + + double *ptemp = new double[pcount*2]; + double *ptri = new double[maxTri*2*3]; + const double *source = vertices; + double *dest = ptemp; + + for (unsigned int i=0; i +#include +#include +#include + +#pragma warning(disable:4786) + +#include +#include +#include +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + + + +// CodeSnippet provided by John W. Ratcliff +// on March 23, 2006. +// +// mailto: jratcliff@infiniplex.net +// +// Personal website: http://jratcliffscarab.blogspot.com +// Coding Website: http://codesuppository.blogspot.com +// FundRaising Blog: http://amillionpixels.blogspot.com +// Fundraising site: http://www.amillionpixels.us +// New Temple Site: http://newtemple.blogspot.com +// +// This snippet shows how to 'hide' the complexity of +// the STL by wrapping some useful piece of functionality +// around a handful of discrete API calls. +// +// This API allows you to create an indexed triangle list +// from a collection of raw input triangles. Internally +// it uses an STL set to build the lookup table very rapidly. +// +// Here is how you would use it to build an indexed triangle +// list from a raw list of triangles. +// +// (1) create a 'VertexLookup' interface by calling +// +// VertexLook vl = Vl_createVertexLookup(); +// +// (2) For each vertice in each triangle call: +// +// unsigned int i1 = Vl_getIndex(vl,p1); +// unsigned int i2 = Vl_getIndex(vl,p2); +// unsigned int i3 = Vl_getIndex(vl,p3); +// +// save the 3 indices into your triangle list array. +// +// (3) Get the vertex array by calling: +// +// const double *vertices = Vl_getVertices(vl); +// +// (4) Get the number of vertices so you can copy them into +// your own buffer. +// unsigned int vcount = Vl_getVcount(vl); +// +// (5) Release the VertexLookup interface when you are done with it. +// Vl_releaseVertexLookup(vl); +// +// Teaches the following lessons: +// +// How to wrap the complexity of STL and C++ classes around a +// simple API interface. +// +// How to use an STL set and custom comparator operator for +// a complex data type. +// +// How to create a template class. +// +// How to achieve significant performance improvements by +// taking advantage of built in STL containers in just +// a few lines of code. +// +// You could easily modify this code to support other vertex +// formats with any number of interpolants. + + + + +#include "vlookup.h" + +namespace ConvexDecomposition +{ + +class VertexPosition +{ +public: + VertexPosition(void) { }; + VertexPosition(const double *p) + { + mPos[0] = p[0]; + mPos[1] = p[1]; + mPos[2] = p[2]; + }; + + void Set(int index,const double *pos) + { + const double * p = &pos[index*3]; + + mPos[0] = p[0]; + mPos[1] = p[1]; + mPos[2] = p[2]; + + }; + + double GetX(void) const { return mPos[0]; }; + double GetY(void) const { return mPos[1]; }; + double GetZ(void) const { return mPos[2]; }; + + double mPos[3]; +}; + + +template class VertexLess +{ +public: + typedef std::vector< Type > VertexVector; + + bool operator()(int v1,int v2) const; + + static void SetSearch(const Type& match,VertexVector *list) + { + mFind = match; + mList = list; + }; + +private: + const Type& Get(int index) const + { + if ( index == -1 ) return mFind; + VertexVector &vlist = *mList; + return vlist[index]; + } + static Type mFind; // vertice to locate. + static VertexVector *mList; +}; + +template class VertexPool +{ +public: + typedef std::set > VertexSet; + typedef std::vector< Type > VertexVector; + + int GetVertex(const Type& vtx) + { + VertexLess::SetSearch(vtx,&mVtxs); + typename VertexSet::iterator found; + found = mVertSet.find( -1 ); + if ( found != mVertSet.end() ) + { + return *found; + } + int idx = (int)mVtxs.size(); + mVtxs.push_back( vtx ); + mVertSet.insert( idx ); + return idx; + }; + + const double * GetPos(int idx) const + { + return mVtxs[idx].mPos; + } + + const Type& Get(int idx) const + { + return mVtxs[idx]; + }; + + unsigned int GetSize(void) const + { + return mVtxs.size(); + }; + + void Clear(int reservesize) // clear the vertice pool. + { + mVertSet.clear(); + mVtxs.clear(); + mVtxs.reserve(reservesize); + }; + + const VertexVector& GetVertexList(void) const { return mVtxs; }; + + void Set(const Type& vtx) + { + mVtxs.push_back(vtx); + } + + unsigned int GetVertexCount(void) const + { + return mVtxs.size(); + }; + + + Type * GetBuffer(void) + { + return &mVtxs[0]; + }; + +private: + VertexSet mVertSet; // ordered list. + VertexVector mVtxs; // set of vertices. +}; + +double tmpp[3] = {0,0,0}; +template<> VertexPosition VertexLess::mFind = tmpp; +template<> std::vector *VertexLess::mList =0; + +enum RDIFF +{ + RD_EQUAL, + RD_LESS, + RD_GREATER +}; + +static RDIFF relativeDiff(const double *a,const double *b,double magnitude) +{ + RDIFF ret = RD_EQUAL; + + double m2 = magnitude*magnitude; + double dx = a[0]-b[0]; + double dy = a[1]-b[1]; + double dz = a[2]-b[2]; + double d2 = (dx*dx)+(dy*dy)+(dz*dz); + + if ( d2 > m2 ) + { + if ( a[0] < b[0] ) ret = RD_LESS; + else if ( a[0] > b[0] ) ret = RD_GREATER; + else if ( a[1] < b[1] ) ret = RD_LESS; + else if ( a[1] > b[1] ) ret = RD_GREATER; + else if ( a[2] < b[2] ) ret = RD_LESS; + else if ( a[2] > b[2] ) ret = RD_GREATER; + } + return ret; +} + + +template<> +bool VertexLess::operator()(int v1,int v2) const +{ + bool ret = false; + + const VertexPosition& a = Get(v1); + const VertexPosition& b = Get(v2); + + RDIFF d = relativeDiff(a.mPos,b.mPos,0.0001f); + if ( d == RD_LESS ) ret = true; + + return ret; + +}; + + + +VertexLookup Vl_createVertexLookup(void) +{ + VertexLookup ret = new VertexPool< VertexPosition >; + return ret; +} + +void Vl_releaseVertexLookup(VertexLookup vlook) +{ + VertexPool< VertexPosition > *vp = (VertexPool< VertexPosition > *) vlook; + delete vp; +} + +unsigned int Vl_getIndex(VertexLookup vlook,const double *pos) // get index. +{ + VertexPool< VertexPosition > *vp = (VertexPool< VertexPosition > *) vlook; + VertexPosition p(pos); + return vp->GetVertex(p); +} + +const double * Vl_getVertices(VertexLookup vlook) +{ + VertexPool< VertexPosition > *vp = (VertexPool< VertexPosition > *) vlook; + return vp->GetPos(0); +} + + +unsigned int Vl_getVcount(VertexLookup vlook) +{ + VertexPool< VertexPosition > *vp = (VertexPool< VertexPosition > *) vlook; + return vp->GetVertexCount(); +} + +}; // end of namespace diff --git a/convex_decomposition/ConvexDecomposition/ConvexDecomposition/vlookup.h b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/vlookup.h new file mode 100644 index 0000000..28d4808 --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/ConvexDecomposition/vlookup.h @@ -0,0 +1,143 @@ +#ifndef VLOOKUP_H + +#define VLOOKUP_H + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ + + +// CodeSnippet provided by John W. Ratcliff +// on March 23, 2006. +// +// mailto: jratcliff@infiniplex.net +// +// Personal website: http://jratcliffscarab.blogspot.com +// Coding Website: http://codesuppository.blogspot.com +// FundRaising Blog: http://amillionpixels.blogspot.com +// Fundraising site: http://www.amillionpixels.us +// New Temple Site: http://newtemple.blogspot.com +// +// This snippet shows how to 'hide' the complexity of +// the STL by wrapping some useful piece of functionality +// around a handful of discrete API calls. +// +// This API allows you to create an indexed triangle list +// from a collection of raw input triangles. Internally +// it uses an STL set to build the lookup table very rapidly. +// +// Here is how you would use it to build an indexed triangle +// list from a raw list of triangles. +// +// (1) create a 'VertexLookup' interface by calling +// +// VertexLook vl = Vl_createVertexLookup(); +// +// (2) For each vertice in each triangle call: +// +// unsigned int i1 = Vl_getIndex(vl,p1); +// unsigned int i2 = Vl_getIndex(vl,p2); +// unsigned int i3 = Vl_getIndex(vl,p3); +// +// save the 3 indices into your triangle list array. +// +// (3) Get the vertex array by calling: +// +// const double *vertices = Vl_getVertices(vl); +// +// (4) Get the number of vertices so you can copy them into +// your own buffer. +// unsigned int vcount = Vl_getVcount(vl); +// +// (5) Release the VertexLookup interface when you are done with it. +// Vl_releaseVertexLookup(vl); +// +// Teaches the following lessons: +// +// How to wrap the complexity of STL and C++ classes around a +// simple API interface. +// +// How to use an STL set and custom comparator operator for +// a complex data type. +// +// How to create a template class. +// +// How to achieve significant performance improvements by +// taking advantage of built in STL containers in just +// a few lines of code. +// +// You could easily modify this code to support other vertex +// formats with any number of interpolants. +// +// Hide C++ classes from the rest of your application by +// keeping them in the CPP and wrapping them in a namespace +// Uses an STL set to create an index table for a bunch of vertex positions +// used typically to re-index a collection of raw triangle data. + +namespace ConvexDecomposition +{ + +typedef void * VertexLookup; + +VertexLookup Vl_createVertexLookup(void); +void Vl_releaseVertexLookup(VertexLookup vlook); + +unsigned int Vl_getIndex(VertexLookup vlook,const double *pos); // get index. +const double * Vl_getVertices(VertexLookup vlook); + +unsigned int Vl_getVcount(VertexLookup vlook); + +}; + + +#endif diff --git a/convex_decomposition/ConvexDecomposition/DecomposeSample.cpp b/convex_decomposition/ConvexDecomposition/DecomposeSample.cpp new file mode 100644 index 0000000..35a1316 --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/DecomposeSample.cpp @@ -0,0 +1,668 @@ +#include +#include +#include +#include +#include + +#include + +#include "./ConvexDecomposition/ConvexDecomposition.h" +#include "./ConvexDecomposition/cd_wavefront.h" + +using namespace ConvexDecomposition; + +// Test application to demonstrate how to use the ConvexDecomposition system. + +typedef std::vector< ConvexResult * > ConvexResultVector; + +static const char * fstring(float v) +{ + static char data[64*16]; + static int index=0; + + char *ret = &data[index*64]; + index++; + if (index == 16 ) index = 0; + + if ( v == FLT_MIN ) return "-INF"; // collada notation for FLT_MIN and FLT_MAX + if ( v == FLT_MAX ) return "INF"; + + if ( v == 1 ) + { + strcpy(ret,"1"); + } + else if ( v == 0 ) + { + strcpy(ret,"0"); + } + else if ( v == - 1 ) + { + strcpy(ret,"-1"); + } + else + { + sprintf(ret,"%.9f", v ); + const char *dot = strstr(ret,"."); + if ( dot ) + { + int len = (int)strlen(ret); + char *foo = &ret[len-1]; + while ( *foo == '0' ) foo--; + if ( *foo == '.' ) + *foo = 0; + else + foo[1] = 0; + } + } + + return ret; +} + +class CBuilder : public ConvexDecompInterface +{ +public: + + CBuilder(const char *fname,const DecompDesc &d) + { + + strcpy(mBaseName,fname); + char *dot = strstr(mBaseName,"."); + if ( dot ) *dot = 0; + + sprintf(mObjName,"%s_convex.obj", mBaseName ); + + mBaseCount = 0; + mHullCount = 0; + mSkinWidth = (float)d.mSkinWidth; + + mFph = fopen(mObjName,"wb"); + + + printf("########################################################################\r\n"); + printf("# Perfomring approximate convex decomposition for triangle mesh %s\r\n", fname ); + printf("# Input Mesh has %d vertices and %d triangles.\r\n", d.mVcount, d.mTcount ); + printf("# Recursion depth: %d\r\n", d.mDepth ); + printf("# Concavity Threshold Percentage: %0.2f\r\n", d.mCpercent ); + printf("# Hull Merge Volume Percentage: %0.2f\r\n", d.mPpercent ); + printf("# Maximum output vertices per hull: %d\r\n", d.mMaxVertices ); + printf("# Hull Skin Width: %0.2f\r\n", d.mSkinWidth ); + printf("########################################################################\r\n"); + + + if ( mFph ) + { + fprintf(mFph,"########################################################################\r\n"); + fprintf(mFph,"# Approximate convex decomposition for triangle mesh %s\r\n", fname ); + fprintf(mFph,"# Input Mesh has %d vertices and %d triangles.\r\n", d.mVcount, d.mTcount ); + fprintf(mFph,"# Recursion depth: %d\r\n", d.mDepth ); + fprintf(mFph,"# Concavity Threshold Percentage: %0.2f\r\n", d.mCpercent ); + fprintf(mFph,"# Hull Merge Volume Percentage: %0.2f\r\n", d.mPpercent ); + fprintf(mFph,"# Maximum output vertices per hull: %d\r\n", d.mMaxVertices ); + fprintf(mFph,"# Hull Skin Width: %0.2f\r\n", d.mSkinWidth ); + fprintf(mFph,"########################################################################\r\n"); + + printf("Opened Wavefront file %s for output.\r\n", mObjName ); + } + else + { + printf("Failed to open output file %s\r\n", mObjName ); + } + } + + ~CBuilder(void) + { + if ( mFph ) + { + fclose(mFph); + } + for (unsigned int i=0; i\r\n", mBaseName, index, mBaseName, index); + fprintf(fph," \r\n"); + fprintf(fph," \r\n", mBaseName, index); + fprintf(fph," \r\n", cr->mHullVcount*3, mBaseName, index); + fprintf(fph," "); + for (unsigned int i=0; imHullVcount; i++) + { + const double *p = &cr->mHullVertices[i*3]; + fprintf(fph,"%s %s %s ", fstring((float)p[0]), fstring((float)p[1]), fstring((float)p[2]) ); + if ( ((i+1)&3) == 0 && (i+1) < cr->mHullVcount ) + { + fprintf(fph,"\r\n"); + fprintf(fph," "); + } + } + fprintf(fph,"\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n", cr->mHullVcount, mBaseName, index ); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n", mBaseName, index); + fprintf(fph," \r\n", mBaseName, index); + fprintf(fph," \r\n"); + fprintf(fph," \r\n", cr->mHullTcount ); + fprintf(fph," \r\n", mBaseName, index); + fprintf(fph,"

\r\n"); + fprintf(fph," "); + for (unsigned int i=0; imHullTcount; i++) + { + unsigned int *tri = &cr->mHullIndices[i*3]; + fprintf(fph,"%d %d %d ", tri[0], tri[1], tri[2] ); + if ( ((i+1)&3) == 0 && (i+1) < cr->mHullTcount ) + { + fprintf(fph,"\r\n"); + fprintf(fph," "); + } + } + fprintf(fph,"\r\n"); + fprintf(fph,"

\r\n"); + fprintf(fph,"
\r\n"); + fprintf(fph,"
\r\n"); + fprintf(fph," \r\n"); + + } + + void saveCOLLADA(void) + { + char scratch[512]; + sprintf(scratch,"%s.dae", mBaseName ); + FILE *fph = fopen(scratch,"wb"); + + if ( fph ) + { + printf("Saving convex decomposition of %d hulls to COLLADA file '%s'\r\n", (int)mHulls.size(), scratch ); + + fprintf(fph,"\r\n"); + fprintf(fph,"\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," NxuStream2 converter - http://www.ageia.com\r\n"); + fprintf(fph," PhysX Rocket, PhysX Viewer, or CreateDynamics\r\n"); + fprintf(fph," questions to: jratcliff@ageia.com\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," chair_gothic_tilted\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," Y_UP\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," 0.803922 0.588235 0.92549 1\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," 0.803922 0.588235 0.92549 1\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," 0.631373 0.631373 0.631373 1\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," 1\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," 0 0 0 1\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," 1 1 1 1\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," 0\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + + for (unsigned int i=0; i\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n", mBaseName, mBaseName ); + fprintf(fph," 0 0 0\r\n"); + fprintf(fph," 1 0 0 0\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," 0.5\r\n"); + fprintf(fph," 0\r\n"); + fprintf(fph," 0.5\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n", mBaseName, mBaseName); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + + for (unsigned int i=0; i\r\n"); + fprintf(fph," 0 0 0\r\n"); + fprintf(fph," 1 0 0 0\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," 1\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," %s\r\n", fstring( mSkinWidth ) ); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n", mBaseName, i); + fprintf(fph," \r\n"); + } + + fprintf(fph," true\r\n"); + fprintf(fph," 1\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," 0\r\n"); + fprintf(fph," 0\r\n"); + fprintf(fph," 32\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," false\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n", mBaseName, mBaseName ); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," 0 -9.800000191 0\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph,"\r\n"); + + + fclose(fph); + } + else + { + printf("Failed to open file '%s' for write access.\r\n", scratch ); + } + } + + void saveXML(FILE *fph,unsigned int index,ConvexResult *cr) + { + + fprintf(fph," \r\n", mBaseName, index); + fprintf(fph," \r\n"); + fprintf(fph," "); + for (unsigned int i=0; imHullVcount; i++) + { + const double *p = &cr->mHullVertices[i*3]; + fprintf(fph,"%s %s %s ", fstring((float)p[0]), fstring((float)p[1]), fstring((float)p[2]) ); + if ( ((i+1)&3) == 0 && (i+1) < cr->mHullVcount ) + { + fprintf(fph,"\r\n"); + fprintf(fph," "); + } + } + fprintf(fph,"\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," "); + for (unsigned int i=0; imHullTcount; i++) + { + unsigned int *tri = &cr->mHullIndices[i*3]; + fprintf(fph,"%d %d %d ", tri[0], tri[1], tri[2] ); + if ( ((i+1)&3) == 0 && (i+1) < cr->mHullTcount ) + { + fprintf(fph,"\r\n"); + fprintf(fph," "); + } + } + fprintf(fph,"\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + + } + + void saveNxuStream(void) + { + char scratch[512]; + sprintf(scratch,"%s.xml", mBaseName ); + FILE *fph = fopen(scratch,"wb"); + + if ( fph ) + { + printf("Saving convex decomposition of %d hulls to NxuStream file '%s'\r\n", mHulls.size(), scratch ); + + fprintf(fph,"\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," 65536\r\n"); + fprintf(fph," 256\r\n"); + fprintf(fph," 2048\r\n"); + fprintf(fph," \r\n"); + + for (unsigned int i=0; i\r\n", mBaseName); + fprintf(fph," false\r\n"); + fprintf(fph," NX_FILTEROP_AND\r\n"); + fprintf(fph," NX_FILTEROP_AND\r\n"); + fprintf(fph," NX_FILTEROP_AND\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," 0 -9.800000191 0\r\n"); + fprintf(fph," 0.016666668\r\n"); + fprintf(fph," 8\r\n"); + fprintf(fph," NX_TIMESTEP_FIXED\r\n"); + fprintf(fph," FLT_MIN FLT_MIN FLT_MIN FLT_MAX FLT_MAX FLT_MAX\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," 0\r\n"); + fprintf(fph," 0\r\n"); + fprintf(fph," 0\r\n"); + fprintf(fph," 0\r\n"); + fprintf(fph," 0\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," NX_SIMULATION_SW\r\n"); + fprintf(fph," true\r\n"); + fprintf(fph," false\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," false\r\n"); + fprintf(fph," false\r\n"); + fprintf(fph," true\r\n"); + fprintf(fph," false\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," 0\r\n"); + fprintf(fph," 0\r\n"); + fprintf(fph," 1431655764\r\n"); + fprintf(fph," 1431655764\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," 0.5\r\n"); + fprintf(fph," 0.5\r\n"); + fprintf(fph," 0\r\n"); + fprintf(fph," 0\r\n"); + fprintf(fph," 0\r\n"); + fprintf(fph," NX_CM_AVERAGE\r\n"); + fprintf(fph," NX_CM_AVERAGE\r\n"); + fprintf(fph," 1 0 0\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," false\r\n"); + fprintf(fph," false\r\n"); + fprintf(fph," false\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n", mBaseName, mBaseName); + fprintf(fph," 1 0 0 0 1 0 0 0 1 0 0 0 \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," 1\r\n"); + fprintf(fph," 0\r\n"); + fprintf(fph," 0\r\n"); + fprintf(fph," 32\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," true\r\n"); + fprintf(fph," false\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph," Bip01 Pelvis\r\n"); + for (unsigned int i=0; i\r\n", i, mBaseName, i); + fprintf(fph," \r\n"); + fprintf(fph," 1 0 0 0 1 0 0 0 1 0 0 0 \r\n"); + fprintf(fph," 0\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + } + fprintf(fph," \r\n"); + + fprintf(fph," \r\n"); + fprintf(fph," \r\n", mBaseName); + fprintf(fph," beshon\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," 1 0 0 0 1 0 0 0 1 0 0 0\r\n"); + fprintf(fph," false\r\n"); + fprintf(fph," true\r\n"); + fprintf(fph," 0\r\n"); + fprintf(fph," \r\n"); + fprintf(fph," \r\n"); + fprintf(fph,"\r\n"); + + } + else + { + printf("Failed to open file '%s' for write access.\r\n", scratch ); + } + } + + float mSkinWidth; + unsigned int mHullCount; + FILE *mFph; + unsigned int mBaseCount; + char mObjName[512]; + char mBaseName[512]; + ConvexResultVector mHulls; + +}; + + +int main(int argc,const char **argv) +{ + if ( argc < 2 ) + { + printf("Usage: Test (options)\r\n"); + printf("\r\n"); + printf("Options:\r\n"); + printf("\r\n"); + printf(" -d : How deep to recursively split. Values of 3-7 are reasonable.\r\n"); + printf(" -c : Percentage of concavity to keep splitting. 0-20% is reasonable.\r\n"); + printf(" -p : Percentage of volume delta to collapse hulls. 0-30% is reasonable.\r\n"); + printf(" -v : Maximum number of vertices in the output hull. Default is 32.\r\n"); + printf(" -s : Skin Width inflation. Default is 0.\r\n"); + } + else + { + unsigned int depth = 5; + float cpercent = 5; + float ppercent = 5; + unsigned int maxv = 32; + float skinWidth = 0; + + // process command line switches. + for (int i=2; i 10 ) + { + depth = 5; + printf("Invalid depth value in switch, defaulting to 5.\r\n"); + } + } + + if ( strncmp(o,"-c",2) == 0 ) + { + cpercent = (float) atof( &o[2] ); + if ( cpercent < 0 || cpercent > 100 ) + { + cpercent = 5; + printf("Invalid concavity percentage in switch, defaulting to 5.\r\n"); + } + } + + if ( strncmp(o,"-p",2) == 0 ) + { + ppercent = (float) atof( &o[2] ); + if ( ppercent < 0 || ppercent > 100 ) + { + ppercent = 5; + printf("Invalid hull merge percentage in switch, defaulting to 5.\r\n"); + } + } + + if ( strncmp(o,"-v",2) == 0 ) + { + maxv = (unsigned int) atoi( &o[2] ); + if ( maxv < 8 || maxv > 256 ) + { + maxv = 32; + printf("Invalid max vertices in switch, defaulting to 32.\r\n"); + } + } + + if ( strncmp(o,"-s",2) == 0 ) + { + skinWidth = (float) atof( &o[2] ); + if ( skinWidth < 0 || skinWidth > 0.1f ) + { + skinWidth = 0; + printf("Invalid skinWidth in switch, defaulting to 0.\r\n"); + } + } + + } + + WavefrontObj wo; + + unsigned int tcount = wo.loadObj(argv[1]); + + if ( tcount ) + { + + + DecompDesc d; + + d.mVcount = wo.mVertexCount; + d.mVertices = wo.mVertices; + d.mTcount = wo.mTriCount; + d.mIndices = (unsigned int *)wo.mIndices; + d.mDepth = depth; + d.mCpercent = cpercent; + d.mPpercent = ppercent; + d.mMaxVertices = maxv; + d.mSkinWidth = skinWidth; + + + CBuilder cb(argv[1],d); // receives the answers and writes out a wavefront OBJ file. + + d.mCallback = &cb; + + unsigned int count = performConvexDecomposition(d); + + if ( count ) + { + printf("Input triangle mesh with %d triangles produced %d output hulls.\r\n", d.mTcount, count ); + + cb.saveNxuStream(); // save results in NxuStream format. + cb.saveCOLLADA(); // save results in COLLADA physics 1.4.1 format. + + } + else + { + printf("Failed to produce any convex hulls.\r\n"); + } + + } + else + { + // sorry..no + printf("Sorry unable to load file '%s'\r\n", argv[1] ); + } + + } + +} diff --git a/convex_decomposition/ConvexDecomposition/DecomposeSample.exe b/convex_decomposition/ConvexDecomposition/DecomposeSample.exe new file mode 100644 index 0000000000000000000000000000000000000000..f90888f0b4228f1870adcf649406f1cad10b0299 GIT binary patch literal 151552 zcmeEveSDPFmH#9&fdL0*)KRB8=+sWzX%lTU={7iNJAn`)2AIja1w!mnJ4I?K&QOFv z!AV>mo{Y6ywxwO#wY%)DRoB{G*W!CZFyXBVXf@Fp#MZVC4O)CD1O(>y{hs^GWCFN# zcYmMX=l6%UWX^p%_ug~QJ@?#m&%Mv=FWqgiS}YbD{$(;2%U1mIzmWX>um21pdGZyH zO}0Ed;a4BsT2S|^k2XfXcAIbMvTuBK*-c;f{q;?^-ujK0@5^8DEsNjk``WF(>bVWR zuYY6FSFWBkX`ng^b}YucdOWo zuLSG@ycfUhHDUZCJ@{Yt*V107(hx^_Nq~8oS$=arjI^A*qR0wjf=fA6CUs(}D+A9y6{bFCu_GOFsESC1Gmo2&}c9X?&aWi7s_jdCaKiU66Ajs7! zn`Otcl0Qs6@hd`N*0Dexf$KBT~h6!?$=A5!2$ z3jF^`foA9P_^Iw@}XA`9^GEOa{Sgt#I*Gd6@|}AsWVe*&q$eY^T4=k zEP6jnRi7iR)JzMVk#@<=`lL$4ZMf(Q_^bEdtl8Ix3xNggNgTGPz5Zx95}J*#pl{Jq z0be-HZhE?UVt=LgC&L9B?4iz`@#DqYHq@17)*dfSR+nbt=joXZwV7H3W5?E3Tpb_Z z4|@l}hdd9rS8{X=1zkUTgfy;0()c zQ=-+9^c^IbP3cs*N)p>$=%`ztZAlDxLK>P=8|>8(ew85o{FjB7%MaCjul%>=HV83JJ!3mVArg3j+QgAZYu51cp># zi3IjAQ>%cz0QDx2B~%~vOU%zz&V#}a|Hzzs1pEQPCj{(fp&2Mt($%xP^>Na^EThkG z=yer#y|Kb(9ndY2`f&6i$=!zBpySa#Yy9%y0{d+rF=b14@L_^c0e=P%yjUrm<|C&i(M#zn*vvyV1CM$1ICyNb%lek^)bHN| zPt}a_*ozF0%kkI%f;k>*F>0i-S-MzEy0jQqkGA4tlEtMrq9(BXHjko>hVZhrLZ22R z^Bx-ADvf@ZV6}jU2&%3e04Sq{Ze&O6C`YTY)UMZ++N}Ncx+_vIqt#+OgxqJ3R*SJ| z6k$@bxb)ffL_bDrdM4Owj#i8DO=c^VCfrQWBj7wK;Tav5ZLa*$*|TTtXzkh41lrpn zgs0x>Zn>?0>f7W*-UbDWlg;{4iB+mu<99zWr!3Zjo!oZk#&y}pPL2PR-t<9s&AuYBo?6=t= zhTd&kq)lS`=IOs9Re(v*IP_*)y%7c)AXsb}sPQLw zh^y#js!&;vSqQ{mUt`Ozr7V!R-Oquma`h$gZ_gf-H&*=4VmXR=TM(PjYz!WgdNESl zY^Y-0VGE`(C-m{;&pDf$lGT1!bjcs8EMepCP+by}Ga5xOVl1~{Svmrq?mFu1ymTDM z@Es5A*Ihf~wz8h#^Yp**B2?VlJ5tz?Z1lSzw*n|;8KFd?^x_B1n(8_O8_aa*Gs6535^0)5ey0VR|LHR78A4x=p*><>%?~v z!9f8h65JwSMko`CwoB+Ograo<{+?i|fUgkr2)LKv>%S$wX9(^P@G*kx1^hX|B?4{% zh?OB)C!y~%!7iXq@b%vi$y$Qj1&ohoSWIw>#4aS*DPSYPkbu_%Bx;|8f=sXoSW0m4 zHKP7F!G{IBl;GV0ItjK5Xd_rD;Bn0Gs7Jsz0TQ)wkVpj&5#E5RNCM<61j z4+;1NK(=y|gkELB3ISgr*ec*of))XvB6u)OeE&i40RitN*eT$T35EsyTYyAeE}>2) zcm%wi;JYazxs~7x0{%6@EdsUzL>HDy;0DHr1q=ZsM!STrm5_auc+SqBL&}UHpfj-< zQPCr>u(AST+AiQx2+Zha0fz~O1w2SFAmFbFx&+)s@b#C8;c0++3q)Js-ApDN-71my zAu_SOHo8edo0)s9fZqk!&=jqcKquoX1iW1e1g0OF4rw2COWaqOJTk;ezC8mV1W43j3H_W2r2=jt=o0XU1YduN72ZYgUI7yTF{telSkCx50dE0FjD86% zV1h%ydV(V_63tA4F9=vkP;uZj1h+`+CkQG=yNqDB#JT_y^%4mcGNE0-V{Zd25%4g< zccFPS8?O<3UBDL!z98UkfX&9N<3v?H4{FJ}?Oad#u!uOq(JjbhtdT_fXqv2R**|Li zX=u`inv?gBu0IbSj}Y7>;O_`75%6VzTz|q6+9M%*S!Q^Aa*H36Dc2;( zs?p{IN0hAEnzU_=v^49xjsL_HnK`__DOxUgI$42Tz}pGF@MkvWR)Y5k_}2uN2-r%{ zBj9X;J?}E_G=gflKL?Oa?3RR2F=2^-mlG@z@Ir!v@35qu-~$4lIs$O5fNv9Q6z~rO zy#l5Hl4o9jnQ)JPnBWs|62Zf7GEbpo z7x37h5Zf)_VS=p!zDCd`;EM!%-e9ra0ExO&LQgVbzJUKu&?n%(5*$3t?3)R$74W-~ zSHL?7h6G#%5OQE-n7MC7fU@%;3AHoVW&xWBDtS1I;8KbGBEgV=N z1n&{>LV!XN2^BG+Qos{$0`v>`CxR9MUk8}j?kmgOot<*AFOB8z8(NxLqT3I#nqRWq z0|GukFe>0r35EpxKEZ&1IzhXDYXK&SgAb@mp&8GHttE+hDA{EEdH>zhrG z1vkE($uuvv0GbO3HR^rbbSF-oUOpa?$60#12jxDhPj`n|;$M-k>y71K*XMe+x*&A0 z$^Q&i-r=jd-iRN9{Y<;Xz09dkw=HbL&csBwFge|p7fiO;rcU=D4x5Dv?D9seZ|lF( z_hIjYozE`W`6O0(1XH1I>9++exrU8)7Epseq&IjHCtS@f*h5Xn9tt>Vu?ikpR*q;@ zgB>;O&{w&w$AhPrPeC-cNn%=x6d!4BK#!im-fm&rJnWLVVfAGDe(LwxzF(#{xa-;X z``?njN7*{`dX?(+pYnRWU?F@h1q9{2g zthz1sOh;GGz_=%{cEl!xjoDZ|u#szMDSL(Xvb)rh6q~BwnOlyat9}}~YUQS`47AnQ zW%^v~Bj^4ReQR;l8#Mr0j1c}}M?HP`N&QYi(X((K(FY{nHXxB)VFm=Rf_zv6`QPXc z5S#62&zYO;2wJVh{5E3^q+D4~a*ktQ+`E}7%i@eyd_ z*0wso9os~66ARNEH;k~L*hqtIEo1ks+_ffG6x^M)a}I>-^=FL(KtrQ|Y&C^|Xy5v? z+Lt(7z4(IYUJw+ky&YyDpA(&;HIkj{hc00;z6VrEn?H;kKBR=1VoauvxZN|2<$MuD zV-22WF&03cnOyol^x*vT>Tk7xDh}fjWH0MkoXOE84C9$e77(Zfl<|QwhVP^h#laqp zrHWY@en383a~PZM1e!L0J@PbKa!32mbnI5%BDXw6eMd2p{*v|+j=J^}GL7~V4s7vW z@Y4qSdPgBm$4AAm++wUU$S3w-U(5cuhL`e&buQO|n0}KUgU}qo3QR2hK z8uow|x*7=D5)=v>w=jxrL!8;Xu+c1$F1^_iktWs~)rdhGktsdjAAsRf+8H)VB;JRE z2gJhyWS7Q93^y^f1f(K1IBXP3&Qg`r4I78FI%52h(zn?mEvz?E2sK1)?9ac-dg3E5 zP|(065B4>_E3x)$?4CV~#Oehud<0w{2Gw1r0c_pjwHV{XNa5;OwEGl_Hgg@KW!$JE zw3czQs!3c0<9v*}no!S4Kz>54gf1mC@*W@;p@#^K1C-eAFYD2}{jAF5*mc{x5$J;r z_epS{CHPFs<3;$z-0@f}_k{54=I_%!70Knr;=Jo8Fik_WL%wzTx1hXUe(&PK=mV&y z+4v#G6C>T#6aRQ}PGQ983D zFx2Sx4o>0e3=r_Br)bsrIA`$;PFadFjHrrV6fFmgmO?z-6Eddc(3T3?33+I13d2UZ zLJJgUp>>Z%`|b%rD}*rm53_Y_?GZ#b8~-l!WH+ypZvGfyeT3c2*q7PYWh@{Oy88q& z3-OGu9D=Qa;F~!F(-ZxLPzKR%bQf(nt6i?aDG#Gew!58x)xbdJU9He!Anw6H%m^CJ z?yq9?gaq^&2X0539#A9HWGg#bPr0Z)?B9%>M&xfW-2KkZr!k_C?E#V%)6IveQ4PlQ zBJ9@c{G|xj0d}Em2@K@r2+!A>Y!QgTQi=^CjX`iOK}1MHVI0uRH$DcNJWF8bwe=6!>&PvH? zlMEezxRms($FR;@zs<+suX)X5jbQjM1^lcDo;i&sGs{bh$@tKaYqmX8#?I*wli#^6` zY3VY$?+*5ZRQ}k+27QNd1!qwq1T?9Of8peJ+-M<&HXyD32c+wBm9U8z-}o&;4R+lM z0ay=BAsmUOAOPx(W+u#3*}_IGL)OH0f3Sb~Os;28WI$&}y4vLeGV8X)VGoATl@8hQ zV^3QslD7j<#F)gQ7&8|4)g*d7!6RS*$Fe8&={OVAZ*!n!4hn$fb^2sjt+6O1`fcC| zHv)i?jjn=v)a4N%S#2*sh2iMKM2=+R-+lx9SUmL`AbZ^*9OVJuvWN8x3tC*L*Sj#g zjEaSv=4hOELjS|jfTgRaSs!ZAtg+AF0JHbtxUf+QqUz@*9oP51X4Us;=w;kSTm6V= zteA&1*AI^$m=2O6=L~c~n{JPNPRhf0ek6t18|;FhkO&-l++iZXG&Z$fQ_Z!JZw97I z@2N^ku(po)qA=SM0AH2gVxU( zm$7eisirxS?q4j_Ty0~HeAIc%!E-RPU7z8i=AqkhAm7!~qK;d%*)G(SL1)%Dibr}g zg>oq3?DS!AkVded&GzEG=;z~L(k~Xj92~lBJaoHjVQxJ$hjm}@gfn3$8^5&gkJXWwh`W!n{vl;eC*!WKtoMQu5nx_{a zilRKSTlaSD)S4Wz2@&JI12T~jnRGm!w0%#Taz_&A|vc^nJxIfz((Q zi?<~g`7s8|&(oV++WEEY%v%@=>+@Q(9enXl@N{hT-56ADd}6>BJRN`c9BoS4q!t{1 z>F*RDK{Lpsy$1`!%?;WNhjAClOZptPZYw?pP6e+eZU4!Jg^LGU8jP5;1x@{jp^w&m$Um7gd36z-|HPNoSrQCF;l_n-n6a2x+8U|C4Nm7D4Y6{ zT}6yTK-H1@k}DUb>PlU%R#6sWg{d|vR27#(QgNzH3P}`O@nMBUEB`N(^af|wXQ8Cb z3;yZ0<;AB!V9)>45uF?FPLErdx)MGGsW02pHLkYQmt6~ndIon6Z5!Nupm(Tma1Z{T zNWYREOb?o_NunfxpTV%;XPe1=t7hhL-m2@sw^^QBbrmu@B(q&*u8QTcX;o~}Xy&T8 z_1d1khYI?X{;}?GC#OMCJ9G-_99*xvUQuDdo@NE=ajxY4mUK}oGU}_jt0`3hKovPC zYKYqhV@r_1@5$!{CYpT&7P|>zD zK$bwxQZ=cv2ue)^6{FEaP=UfB6*UgQ&~RaT(7M_MX7~!05|k;`XSh>~pg+|4S43d5 zUo_NHpGI%1{ndyrNrzcM9l&zb?M=73hIXbVh0*s^wcihnOLCzSgks3-&Bah}?J%DB z1^V6TCwbBBR89NBbXz;}b);&d>9(kul&V>pZd)pXJb&=P0on0c!Zoc43usHS(|-`y zu#h;=>{tZe8};Fc@x2G6B3K43sV!2UzJUA4Tzi(LH~a5FDyqa@(}GT|$fd17+Px|b z8+9UB%OBO%P6;5#Lx@Wk`LH)a*D&rT6v{#1fTbV~Qe8RTX&-i&M-#GtL)TsX)qW?C zM^)BZM3tg7E)*jpxIkO(0iu9C80x4DpmW3J&Z-aWsTw#_S94%Xcvf<$gW@$Zx@{$TxL;0{--jDKXeNPwNTMBc}M*j$Kq_B&r z&#JeQfS5{Pw5x0gl|$P#E&=6$_z4uj7-9h3Y|mzYj6a?J?TF`aB4(|MVHc9!G9(ei zb|cmt<~rDbP-F*d@AmiLC$YU0(0WER`rFyyqLp9LS97MeBPSCc_2EzYvgE_kYDC_R zFh`*vJUO23gup@UaDlUP z3oU);m_U@Adargqe(hRBHYQqx>ak0Uz;OyY&WLzrX%RO<-ej#u^7>R>zseg>c}rB@ zQkAznSz9W3D^%V}l{cjFR;#?V$h)mJYYfDE#?oU?hq(K2q;BG#D0LIIM2NMeKAQHV zTkQ}s`67TR$jmaS>m~p7_5;0XOKQS_Ugl#O@<8mTYN5o~Q}zRgDCVWW1j6=It&1_W z%x6Q)m|CbGInv{>Fkw}CzXeH6@S)zU^Xo;?wVbEM{fDKIQ^BfOUVjt>B z&2bI&rsmj(cBLk_r9DGCvprMtEOEF|;e=+4fps*fP%~ifgMOI^>Mat!I{x1!-y}9n2%dB(q{q3+ zm#STPMLOg|D3lIS9@b)yPO^n4Lt4|JQhmF|%- zVBY8S0{sQ8P_MFS)8NZy*QVLAzt*NX;Mb;K@7AWdv{`Oud|sa@J)LFKYHj)~JKH?V zq18I{SuVZajgDf8Udjf?-h)pHl%ZJIxDg^Rt8kRp8-JukpY9P8w^{>hNO#{5#^3Le zzY1;zQ$Q$FU&L>K8Y9_&Yi9ex!JTbPoM)!`naVj=?Vm5js?CHFmEfYDnI3#U`XvrS zGlE~J8)5~M#hz;C1__fj)$W4q`6${49unC_H4U-}vJA3+aMw^TDma8iZ*VtsCHU?k z02U;qG9WxeIfD>mDa>sCl*2FTuT0~doI&qaUMUSNqGUl&)ig)9Ou)qssA&l-K*~z& z_-(Zh?c@*oIku14`2l}mnIEZ1qQ!*lgRh~T0pWamY7r((BPIv56f;=?gNG1}$zoSQ z$T`r1dreS4at^*Oq+ug|1IS19e(0IOXVs9QzX9ndmq}Pg(O3^DgE+MfIB{S|4a}*7(ID2^m_G=8IbJliXw5eFL(D0DYYR)5!_ z!l0Ri*Qqe(eExsg@vX)9!fHbbIJQB{2avXHOWL-9c@^Vg5uQQ5%}@DXu{GDJLB-7E zLNYf=ieE0Q+XnlFPNb%61tTjRZOUNp;5J4*BvBl164-HV4@Xw9fj+~N*F0=cs2HC$ z^O6pKq#g;S#?`P+qfQ)r$*NB_tK|$MpW!!kQMUT3*oE1OdBkDIDUDPrqnkftvh*w+ zBMHd%7Hns|ev^Ty@@ARHo|6J->)>uq%v~Y{d_tZaiycb8oE{wNIY3b$)4^=0Oo(h7 zsGra_hKnq&uyN=m@}6y=#tufKBe{y+pN+=R5sy;y&O5X1Uj%08+K=s1{Jd+yU}7@! z!AR?eoq4uP?($Xsa1G4Y*ywfTHQ5LCPsEq*(}R zh#41N{w){=j~zJn3KsbQW`b|nhGjp1De@9FrPg@$6b0~+G0Hbc1E@Ucv)Bj zuqWn4;Z`6C;Fm-Q0H)Yx_dR++8LZIGI|ndW`rFt)jvIV!=(WL@)sXpV@L7bTu3XFo zP_q%^$;GU4>IE|s{V;AW>pQd#Sb#l*b%ymVG6}v2jUR^)yH=r4vS+0V7du7?Gsc#L z@*;WgTZ*=p%G{~|RB@n}i%f2TS?Nk&j7$OAKuK|!9}8eyy_|B#OMxkgqDf%mfW(ki zz+E62%-Pk)o!y{08w$F5&=hlS0Q%rFW1)URfBV?0WZmTa%2sf{kKB**Ui8~rmgWC( zX>VD2T(Y_{l=7Mupb09R_LhSGeTjbIe_wou%!WUC)NHsPeF&vK2>Xw+=c-~9^5yaC zs!I`(&%moDB&J%OiJ4$tq>P<96;e2BDk9gEO6hD2c?Yabi6Uil^%lf0Q4vg1{T>Gb zbAZM)ryzbIBL;`^^Y{>z*Fu%YGd2&DD5B0OS)yST?O;PF1G11W2L*<2Wc7KJSm{U? z^`HPGxtb06WEzurMuUo0I#QEZl2w_egbF2lQ;VdB6)+L7r=R<6ESFYoXjvor#pG`oL(4XvRpnre0^H&;QTEuNPp5Lm1XT(j6iQeTNK?bniu|7765m+B_ZzBaRDI_?$do zj`T~|Y^S|@fhETs80kKY^oye@y(ZtBKMg!^{%HJ8#(zo1c^k(0`CLl6-j0d`OhY}r z@R*u9nuaoF+BG$1J?sQUMgcX~%3QWx;tJA9cx9*nS-@{|0 z5OzU*ul_6!jiIoec;|loSspsy2e+#d2s}SEf2c=gZzM7{E=cg4>F(e{2M>V6z{%b} z6+%GHOqR&uCcGwm+7hf_Z6kW+kFflXo2#uE8J@0J-~`+aFj+Y-U46=u>^No71IZ;{ z$HDy}J%FpX0?$8WXTW6!TvE(4Q>)M_f26ma97TC@6y?eP1CDv|@N}KA{o^;2DYk29(ZBm%w~~O|T6OH86X)8k)-9pt|j= z#o=hnxPY6F-v8%`w_fszwcV7WLTLZ`-pm*y*WGF+HWOD^_xzp1QrY5AP8Op#m z?TE6jReug3YMY2>0!u25zEuM1B^VOR2& z0x9icX;}2Q@tNlPAa%32CwWVu6c4a?saYJhK{nzq*X~W;VnuNv3UC|Sb1Jc|Jviv> zehX|6#9Fobrlf6NvZLRgZ2Y<+Xzy>Vil&%Rq{~e78dZ%q`+Kb-*0rO=x^|RUV!+mi ztuL{@>A0&N9PHQ%$Khud%u8%P%YF==fYSgLvljgey$7vf>B$gcjq5T_!i?yj4tpRH6G+w7J>*?CL#s%LV_upvlb%=$JPR9|2 z?bOb*u_=7;`G#XnlV03=uqbT2fm$^yoQ{ZZKRRv|(Lp~?7(LXU})b*&MR3xb;S!L3BEKk=(f*(;n8&hEP@ORN3mx+T$L zm+6q38Sc@U;T@eBKA9QC{ZAX1AjxJQ62C02}BV$&0+GO^F5WqQbrA-@_~cIUX8 ze24h6=Zc4OMfQG)6(>z({5woo$JKO%CW*cuoxDx2(GQKK}H z>93wQ|1brv!-3YA`FB;`{FB*d9n8(Ydb&Q7Xj z-MZtrLTzz&{tNg&aXjPfq+d*kUO0UnPhtQ23YI*t^RC;~^l&8|UC1sz);(6(1>LOG ztkC&LZN~YCg=WghNyk3D*@H=J-A3aP*aMci(c`UD$OD5F?0{S#s+4bIx`+`&2Zwf= z>xNT5pS9ND$qK)F171YEu5PQ_aR3_~%Qmw5^_m5*zBqBe%;M zlhp%jwHpQ*q=zJ{FFDuDHXlgm=dz(1m2E1Fm$6%b$N5NIL7{#*{Q8oP-4TSw7djuQ zb`_ctkh@7o9}TeOVdKXT1SIMs)f25y3PX7Kfc@`Hz#5D5J04Nj%7TLp7Y%k(XnvOd zucC(MK`Z?jRJip8-y_jUS!XxTSH*H?9s;EY7q*r4P?I$MI}(RWl*t?>580&qv4aC4 z8&Z=DY{!~gu;cbaL}i9DfZ*0lpKA?Ua9UAU*r?H%%y zvMReBh8;zaP9)M(VcKE9l!?Zvf0E3x0Di$<+*`sq1lbFW8*tu5ZxvkMqO=|^ zVwMbSoCVoq=4-H=q1D;omFa2dgex1o5KB|K%3}td`dZ*Z4q0V#N)y&UWs9qd-=eQ_ zl^yNMtobsTI_yYnD};T?`N*^a978zb*E%05WD73ie6{tRQy^8rxRRZaMXM&)B(~Xt z$2y*X40R3j9F+EdIhn##bx=(YCARtCfQ=Bl=^0p0ae15aS-j=P&% zjPn@*@u#0Jd0d7?Mfh;|!vb&p4(S$sk}9zdPG7GwhThr}aT<(<%%C~W6QJRzSlf7>i)+8J3$x3k&)iZEfcI(qd zcn*-R@}*jRYByokXN{<&ljle}iKGklLZmqJ3l-`URT;P^pM}nr*yfrOzq>7XYPC;t z*&aVTm*er7!BZW$0PkCfV>8Esc_O;wR=pR;Wztpd&uTm^Wtrdr_h_D{Wf9lbc(pY? zZ4GY_sf5f^W`avwgUz@@AE)B~kd3!#YwX$=7LMM$Q}h%3_Ng_t_(f=*&Dt|uB${a$ z9@9tO!En^ru<-I+uoojDsxA(?F)G?D`kCNtnJ z%)KUSRQkrc!wu#zCfIB|t^>EU2XN6`zfd31ZI30kyKubc>^us-#A@hk z4jZ@rMx9r|T?D*94ySzJLd0c)C&x4km15yQeq@rUS`}dSKx(o?jkeXxvawWaxB#cxdMkPsqZsUBcT6Ooads);Eiz6awuMpxc3(auOU-87m~f zi#9N%(=mzhsZRe|CU^QJL3vyOA8a)i9DyrmD})CTPEE38VEt4+YPmpO%4UBB+qyF~ z4kcWysKyS+0|=#&yo802q*)aD&4S@IB{;c7#Xtud7d-L_X2xz7WvE*7m#GWf2m2h`TiAoRNF+d zK&26?-NWuHsxcn+J32o~Y&FU&r!#cC8YnjVdzd9ltgZQhyp+xUFq&-=>mV};u?#>! z%``=xDB%@ine)#B1HlEG>)N&{tnkvdh?NN^wv_YjS%ChDMvs+ zrIhMPUQ|7A!1gHWupF{7bm4&QF^XJ$z!cEBb-=cDOpKbVqw^X9`TYRev}6O5GN*xt^DP<_yNqrsyye;jZ1ml{bgKc9cT>uDY#U{ z^xZStRXe6#c`Z^NeA%*6BG+f}&`I>-Xp4#f=!YJoD7wrl**`^EoTNww@iiRn<2l+T z^pbe9T`R`4>%UL0QC#bKDaSq_x^pxwU38Ch$|Tvk-h0QO%XX0tVcF3w1X9I@uuN<-m$#%jdq1HZTc z99jjf)QWbXW=!P(F-x7QdnR_IWb4fio>>D@SX(8^nPW|ai2>gSuZYCWcH@Irlo$x* zRe>f`647;_WVHDvVM3&;Vmb7~>>&>EgbC4p#30?IQXbtT-K1M$pgpfTl)#9*FX>Fg zLbAM`$*{0885%VyO!SCFgV=<118c!ZXVk^+nFGY$<>AcMAe~E!JU zI1;+DNf$}d_`D={HfaKroCS{+q3P=z{gbgraA@E3=u1`8FHp&k(qO;74#^!zUgOOs zUno5zhC-F%%chKz?0G5vY>Hdz$x8_^1s*64#7!>9ODM?}xmen7Ws+6ZQz~V!2(pZH z%uFcHmN{R_2szB8ifmG$Bo*eNt3(pI=LA_N%aB?5Z~%H5G7}_nvMQ%is`FFEtIAYL zEeSkOJdXO6x-8IuCnB;==7h z^kt$IOloh_X3fv;ywsYWwZCyaH?Dwr7^@9DaJaPu|GR(>Mo>E^2==NtDU8X&>(jo; zM@u}~H|_ZGYTxAU5s}RA*S_gSd6r>O#JI4g3Wn+b0}Rtm43rW7voyb7@h%d(-C zM=w&!1wYv*+tdoyLHt-0+2Z_agxk+vNzSe%+b5*tY5~qX+-I(a?5jz<+{*4F;`DSo zdoXkm0aLZeTd$}{WL1m2-mornZ1N~}#-a!l)CZ%PESyxa&q+74uerXd74b~cO?Rmw zVwcp?NG|X~bOo^HP?zCQ_z^Be*oScC8OtJ)Dsp!ND4`Z-)Qcd|_xK*j)=k&&VUCYu zy|Ea-cnHr~IBH-O=0R}TEB6+(Xz&k+U#(xn*u<`aX!~}kF%r_QvLQ~p$}WE`_-izy zJoYU|i~99)WR3yXvI;eHVX?kEp`hRZL0ZBG5;nAgo2R)cE4??)r4= zUKL2U4rYOaS-^oj#yW}%9B~Yx%+gaU=}3wg?Y^FU|geHZaTj6;_|qfxo4?<@qXw&Du-hHjf|C#wDPVR~I( z=f7mbzR~E3yVf2rh|dn5+OW|^LgJ1X?ot4$wz-Z-*Kgc>ACRu^+uR2>W}7H3%UP<1tVj zuAB(_%tAurI`nNLn_J-Q@^N_J66$>9{0-1qlhx9yYPM=a=SDUbtzzRqBp{l9q^b*6Lft;qyG|T7rj*1o+xy7(GBB+(&E}YT4V{~ ze7Xm;1vzXahw~8-6~CU2`AM}R=mu- z2QnTN2wL_??}Xqh5?ZiG64R_-5^K4CVwGRdCW?v?hTQ zy^OQ#QyBf=pH|0m?D&^QVlzsIjq`Scg7PfP9_)4g%iB$$c%$*kA)z=8Ul5g)PM3gR zoKJ65bLWxHjSrGDkP7DZgS=xH-1)Ta!JuLG2xRBvbKdo198e@3p+hV2iyp>{JNL&w ziIJKwb7P=W<^~De>EQH$X_EMzopV44WGja*RHq-R3cd-lmpi*!aaW4;O#G%mU*ZoV zM@8&94lXqQ!1~U*dvSu4<=Cb4r|?;i=_8_Zz|{l#aSfIW2r-&FeZ%&CRf08@cJ1sa z>DnI)ppf@w)KPo0wz2cxNtk)CB&^@qc^|;_-JSR2hs5zBUj;A*a>L>cCHmFDOa*EP z;N%k*a)=F%Cm+MFOMh4C;5bff?8S@dgq^kkX`U5TQWF^+V8we2Qh{xnJ262 zd}c%U!>s(e?uQ@5PwcD7n!@0~>dDu2OVeVX3k3%{-bOu@m`vyCd+UuC|3y~avYtaf z01KHZZ-tGga`E3LYYpfRNI&)NhaUi9?E&@EEs?7qtO>r|(FyzGy?+NB2F_eyfBchr z9F3hzmRs@TfsJ{!O>VCH?os>8eX=c z*AvFix8_!kB3_TrzMs4HiH9lX3uCqV1$x|KMXGhLex3FO9TI7cOPEOE4f`Nxm_x`T`IXpHzFS^i_v zet2S*rSM+bZ0vHcvEHn!k;a=1H*1bBIDfe_S?Rf1!+MPgj67&>c!SCQjn@+1`?PE&~#SzBvB+DUSlR8qZIU;CE^f zLveoDChv6XQ63r^-x zIF7E;33Iug~m;s??hIH!5^7LS~ZwhY+rmNctM!)aXNaMo`O_j>Gl zE0@L={qwAOaR8&{#iCEQTfg!7zg75paDWM6*VIst7rNfSsRP7BV3@B^28dg^wgeKr z4y^#h@+B7*z}lbuMxpjKp5A%!IAB;B6TvC1@%0^<4C<*cUj1$syBE3SowW#n()tK$ z`5RS>OKNecTDY>(R*p@*S(ElPFr!_c-~p@S97CVu&adG90gNI1nKjDjfEt5Dj{^tGwsli0ViTvXu*Hg| zuCU9=c_3VG@cTa)G~{;uh1@RWcI0xq|3Ypza`XLA;y#NRE`XebNK%K`dG21h^U&>} zs$#+hZW!@^ifjnw_E;SrP?6ATZtq*o5Wqz$9?+5;6w6)2pz9iJ1umQ*a!8SjRL7=7 zHj~t8!5)a^MqF(yp*G>5wH)DUh}tkFc?cy+BF%srjVg8c8X7vtd-i^v9tOBJjy-2m znbk|`5z`tTI>=k(d}*)Fn1nJ(_q??2#bo7+Sn^Z;XOoU+wQfI^k;HaZPbPB1rDJK9pJs4{wY z<tSTf2)dDn74UBmeeGYQSSWGt&k0Ju{Z! z_k!6xDjMFQK2;LU3L{@5Twp5L36$s2fPe5eDAkJ8`9cYrB7liCq$b%>BT^TkTstm! zu@37hDu-_wWE$kUXMpLdM#b(=IglIKf@hn z2dGD~!FbCgQr~PGrw&iQmFfiE=o*ZT3&LqA{#R@iN+6RMFBh;w@?g;#o0Lo2;NL-8!qYer#^|T#ahlRvKizR90oykcj~L$ zw{kC4CuD_Ke@aNh{x!YzMd3kqWpT{ooV4rQaYX#cajW%K?)#JkUD+hpN1QlX0 z7*wDl6fu5eM&JpHZzpXpGJ(P^Vq9Y;7_9)5V-#ei^1m6U_vx>q+cP*mG+G7l zfudHswgQhMKx&H39KKHYD$-7P0%?3W0k0+?ZLBpt>tBNRF+b6J=Bv`{4)>rPu(Lxu z!DaM}&Dp)jZm~?A;fjwRnBlVQ`caTBu+Qq}W5jCp2#2u_Zzkd=tVcMEjXF+k@SX!W z0b@HKI@m<~dUQPJz?Bv6IdEFzK?m%F)Qb)<#*82oK#>v%MD7u)@vk!GY5{+Rj7j@I zRK!Es9RVNEa{|dU#Z=&5Y0SZF<;L&#;=Tm3;GI%tDRAEPGw?axW+>9vY1jUw?Si=J$s-uH0E1+v+{Yexz;*{PSVF-e))&9LYiH6nA+JQpSjG})npujD z4Xvzdz(#)zOKPEgI(uY}A5({|5aR&CsVhcf!*Eg?kI358!jaL~TIL;rK`;U(C^lTD;BkY z;k$MV6bLjyoMaaHYcUw52>K$aMgB&Lw9+I(2(&kcbD0;M zW*6F4~WREvmIp;~tlWgRTrqU|OgQd=BjAMIuaAe6 zhn0;|9A>tNG5Im@-fRaJm{2|VHWrRF8=oG;0L=92PLxs0E}ZpKe&MAM-qH0zshdvs zSb6egDV)17hs@Vy+U0ebg+6IfQ20AN=D?vzz_(WAS|)B*5Z}!WXIy0bVC*s5i>tF2=@W;y=z-tq(Xm zzlyftOLO2zbBnFYh-|AnUS-Cd>)6z#wpI}-p)CW8K26% z(bLWg6?k8au6o%4i{@VEP{P`Lr>7l$luAfbRg@v+qaEt09woBPSLUElD*2A^TC~Yj zI#-|^9u!;ws#D37=SOTxyG|yVqki#ov141vsh+mw?Ee?j$Lm;*gE9a%k_$ z=&w3EDJ;x!>G7rdGou6-Z&Cp8r%J4HPL_bVqxnE>h~ zJ#!8y@!s`{v#V0Ef30Hv?@XYRU{1(i{Jk@Te36QfnQhAXh57GPkM)>Vr+MfH6)hX| zqzdRsVW9WrK6L462uJFT|G;y}^ec1(`{EbyatP*yxqd(~?Q3o++g}E=B)HB84)jc& zLX!pfkZO*@dDmW0S_Df|qH>eP+4%s%WpBWc;SRp7+cxQr04G|!F<(>3J~gbr$_Zyw ztB!RY)koG`g3o$B2YoA}mlS9LTxXdT|1)g8ZrqQZ&|nlQ(+K_8WpTiAtJ!`j)hC{@ z)g(?iSaC-ezP^W-l3`dwi@hmbt*oY}hhxS=9fiIWK~&gwl+=Utz&<>pW2I*3mUt+R7HBh6{^e0X%) z?1sq4w83Sijs8YdT5r7ZAK+DUUl>yR!fLfItX2EMI_wMO*{9@87ivu1`-%fr%a)TrfQMb7f@ESiU6OOu`QdMZ1CAZ29*q^p9c zKZXz!l^DL!LeFGw;!8y+^XyNus?D0DsfY29oFfj)tjLOF%5uJfZsuLfR+vIu)w5Zg z%Llh1-$N>q*#~A!)6kKoyaLhkFhrI<#gU_SSC*b(S(!-7pipXG)Y)QXrWwqf<*21Kqf4)ln! zAJZ?U5?r?%kA>|@~tp;Z62#asG!XQ_L-kU=4T|DJec(4_RD^bkY}- z0gQ^olPuQkg5EK7Ft`K6As)mZ!B6}W=puQhZD<94qX;GfY!XCI210-DABwEUm6y%K z{(~qb2VZjf5kepQ5M*xLPO1Uv+{xzCcx8z*(%Jp>lfV;qE1>~IIDg?KBS^%T-otbH z`$h0UKSN_hCmlcay(Xmr;sPO3khy#^4|d~eGV17^m2TXz}dNy zJ+55OCHor$Wm+Wnk+E7Mtc~9^W|HV%zy)ib7@{j);}sA(cfFb~ z0(=t0oQ;PzD)gz=+&M9T4C;Xh^5-mq}O5JW%H@p$-)(%s%wVtGD3;6u2b~ZEDSDbh!mPdLI*a z`_Zj@zQe(8jcsP4*B2b=cpi2<<+QTEjjy6eJM_1cPneT_D!48_e=IG^@Hm3d0yExt z4xJhEI>P0kMbLU=lnytD=c##y`Z~_OCNvxCu&h#PLi_QBJN>+Ki5q_Z#2w;iP|!o% zbENrIdh6`s4KB4QJqqf7+GJ1LFVM~l^{^*wa;dRrl~f~HYl25QUR1MSK#usx$25BU zSy>7&)i@g#Dt*hG6lYosv-ZNo;U##n0r$~xH*xiZGV{T|K0JpvHSX%LYH{v0_Tj{} z1D%Kwp3`x!ognC4?hrKub9tZJpqJA&<7EeOLsW+{GY z;-;YEaZea9&jA7mS0LPossL63sBD+uWsew@d^TsG7*1Opm+x)eo9 z2l=ilRi+9#AE^*k1ziQIrAPs~pQxa=z^&BmTCi# zReDW(iaJ?5z3vZS!?oxl9-!n|BcN~&YQ4Q^ZsNJqGh_ClqFN*lj~glq@n%l{4~w_$ z8z}?nw(|j1%CdEshVWp=%aU1sZiPHXLu*sBMnu~QQ+{PH@=roBI6(MZNs0*rc)JRc;X?f35yB6{JqZczrl_x{Aws6MCi1JGib@d1>GOnW0{0MDV zG)%>Ay<45e;!umm`q`!dXI67qYjPQPKgInSL`z2vC?@`M;b#4`vHk@jA%>%|Pd6Jk z;#dj773ij5!Exc6N`HWM*J3=iTnXJ7z!3idzF2xppX0U8aV7D1Ee4_9uy$f7W_z`Q z0ooZY`uPKe5VRRR$ftO1GqoU8N-W#hb~*2Y`B8m;qqZP8$E8e^P|a3<2L1vY=HG!Q zGVWN9D>8{~<2T^vx=Z8E3{*WlErG$a1$TEGg6stSuod;{6EydudT=IC2V<8*4{D}I zbM7aAxRwEf{|tMcnWhm?lnt?hbhPc=47tR1sVN=VGe4u*~BLPHiHV zIC*+#KGvg)t$X#CaZ7j=CGjGC6(w<0Uqwm01h@9}d2TG7G2AZJFT=wq7ow6yS_4<7 zD4#}YgxS7<*Y9K6Dwmf3GSR;P_p|(7QVpIPGS+RwcW#Z=xKP<#N6uP6a^Fi7J4()m z;%I8t-!6M2_~+OcVS1qXf&RFh1|em=1c$p|J#9d2xiKEbt;BY?sKj}gU=KdSb?hq4 zBn%TC=Ahxhkuw;0`hcYZ&8L(pMN$dfQScy_9R^E&-K>I4SwZItKR)!)0>6^o#zn_j zgFkpmKf;%n_N`T{12II;maLZz+A!8yv}cc!0eIgVl~y;ue5i#>L-opfR8dREBvc)u zAu`NK;I79dmLI*rs$d|E+ZSHj)0Ws?+K0^5Xigmr!+i0aemgkWD_scdwN~qTs6aBM zivkede2kzPkBecZGRim(mU8Rf^;L=Y3c*u!Iq;7>{xH7X$aOV?|OZ_{*9BEN0m57JLBZ7#Q5}9OgSJ&w|SI=#|oDxVdvm3?@|p< zX2}J5+O0}!5(74_+AbtEvOV#i@{9(aXlR6WHy?^~JG*Yh6b>6s^bXm=DCbW)mh(Az z9y7}G`X$;@JB~=hE};f^2n+?gR0^6u0@_uyOKDe$NlIQ#STJv)IR;sMNPXX@tcTzB zX-11m@sFaBhmw`}7vl3-BXCrrLz*9(J}U2)+lsc@DMtAHJG>g!i6-KL3#!Dpt%&fW zdcvcSkJBB^7(!pY-e7~RQGX7dEjQNvOD5Bay}~f!)eeS&Mi+fkPg_XLn3%1wLJYT@6-%_$RS4fI(zMh@9?U6NyQ;*B3L>a zO$1A^&2ru`1tYq_s%F}~HfLuch>0qv<5mHeVrhzV!(lWQSVS+#TN$amtU!D;1-&2_ z9~RRLX@n$E5zHiz3%X1z_M=eQahiwHRCWS*w|x???Z_FVJT8w|4{S;vaRWJ?x{6*y ze1SW4Q7PuBG)leT!XQ3lHxmU`B=OpS8XJ9=IVS1Q5hzU85B_#=&tM;~VuTJ3{su6f zTRoT#8H29@#sjOkkbyp{|0$j12A|>=IvRw+&Gp7om>d$@J>(HS0*gsi4%Wxl6(fdc zHNw=xadHoaYoT!9S*!9fLt!v&sqyLqBs8wp-AmUvKAP%gU~uSdyG~(vSdz)i7Vvpmia>FM(Ald=iUNqR)XN%j@HRIP@RP1ksJJj{|x2 z*pGi7f*YCH!~(-Vris=8^BJv(Hr-{|&(*+O>wv!+Eux08bNLL_B)e&kX|fMksV*EX zEQGEx+Cn`%GCUc7a!qEMBhkmB*6Z7yg1fxv;O+?++BD4VPHIa1>cdM(NwH`tyKG3Nc&p( znco9}U+LN}SX%Jmz#4pl^Jn-zEt`oID_Q|Ij|_}?9J7C%#W){Y7(c6vqrX_k;=;xF zG_DE%-=g80vQ1(rnbAXqb?XU2}>>Fwe_{H;g8E@^k_|O); z?k@Dn*?Ee}3GQ%o@&j^-;{|N%L6Zzmxsu(@BsrRl8tTlxg%0gNA#l?t^lrb8#4bQ* z;PblC??tGkKI5Vr>ALM42>2u;faAGbaLj4ao;?w~>o=s|X5$M&$Kn&@owpnDge91q zU#|6#ntFdMxMA|z;}c`{wZ|vLtTn@*1ZQus&+Ob8yPzrD0{yXwO@f&j($BS_rl6*B zV!QzFQv*xB~)@+XlRPuOBz} z#ci%EVEUP++i)LLHqUJyVyY}N#w>yXJ`dn}EuHNI;eTQ%X&8^SH6M(j~&2H^Yx0T}b3DqjBhEvfJ z12qdG<^kZ6@0#DRBB;*{Ks`3Gl@#v)wypQyci(--UfcJ_;LEEo)8_`nYqB?K16F=9 zgiXg@x-9?|)Y0`y$91r)kD_p#h2l~A1@joYR#~|eJWmffHZhy6k=hV4x(Yr8F<>SCLcDUH}aliEQuL|k- z_D!2Z!)FOXe7ec$VkH>*yp@u(-hux11Y*t>n%1l%X#HHYj&UQ#}gdmrq+Y_@>5rbJs)N+L-4 z?`9LuM7$!Ka0X(tjW~(kbk<39;&Aoi3!;0E;S+1171byw7#P1^&aQsUe~aW5jo$j;+9fNL)h0fNszXhDz zgLzPcj|^iLLoj=IO7swxk=z`aW0yJ70N>Kg6~#lrSLLJ6pGWA-EY|0Oy-m)9Xk$C} z9m*CM#8;nt@YUzubLGG70*RGI*rgHH0ZJcCzg>PE_B-!u|CtnMd@uGt>H`6&-b3N;%(>p2Cy)4VfBX;%gr=&i<8xQTx7xXL)SoHtLtBFQl))*|AI1%g(QUJ> zec`4CCrS!U7Br(6s4p!%~70rV%)??3cuv=&XQ zl_tJ{w{oS4>PQKwoZUPx^RFR-Dl8BG0_@sChYK{rQojXMI115^Oxi<}d%G}MEv2_z%Z zfrdE3u(5uOX;3X9Nc$>_LK&f@g5|~|&0M6;!M`}nj(ybR-$L;3MJE617ifHl_YC%B zKk%ih|HIz92S!z$3*VE>B-z5i3_93Rqog%zYNCw1Ev-i3@>;9}~J+}oJ=#UvqbqqArk24$a8tGYwI1dIs z@R(Ya;njn0Wzzo!Oq&AJesHSf8_xJ>XnfX$w1eiws(dM}McZkKQG*FdrK_%%!J+Pv1-`^>?(tha_I!acF_~+$xS3FOC;kW zFt4v|UuLthd!FRZ189vcaYs(8QP-}p@$V9M-2IEV>z@Vj!Y}4>i0Y#!3EpL;S0AZS zXW1F#AgDI3rVt3oW`j+ln^6sPZunA0=`EfgmnOtrf%>rezBCiOi_G9)@vC$-tFw5w z$kW?8HcmvE5SvmZjd_=$aJ~fUXI{J)I1y>y$)Lva;3Ec3==<(JTBo>6mlDIy;=STQ zsGxWHT`+#83-Kb z1YX_zoF*}%9w_ZItleo^m4%olDA4jeCqsAydNz32F)72(sf2-tBT{M9vIBu6=7?VY zB35nuPGhXj2ia9w$Qp#u1>ge>BJU&+umJ=_3Z2U|2w8>cW~V`1D78p~I9qBl3WDyG z0~hYQ1%XrwQ$e8pNT7|65}XJ!P^Ul!H*qcFAz{mg;f4>Xf4GT3nrno)!$H;a&L+U6 z4zXhHcYtVf2iYCqllyr5JmN*Akf(^Jg!px`J@8vP&rVlP_$(grv{J>hkSEO3z;hFi zh&?xHyeo8e`Cj;lF69(Qu%NlX)1KCE%bbCkr%53>R^LOw==mjf2HJU0Q1y$|FY8G- z5v~%34GUll!n(t#sFV9|;C=PT-8bI_W(o9p;AuK|U-C4->f=!MD7d(Lap#+^8u(o5 zO9D>oJCta6*=bgvAs6Thk-y&txxux9ikGTe?K&6Q0-W<$E0Rbzf@Y3(k1y3j-JR5GFm| z;l(`-p2_7tNAZlm($C*F_8}*JrY|cY7Y!M``}z>=->84R+*2gnSC;ijCulj;B<^~I z{_cB7{vLX>?_9A-(R}PkP2#SdI!gYY9CbzFE;-fqJtTimjyflC*MmAr{+<*S&6(ao z`yb01?F5^iGmoI=3f8x8kwoD#a|fyRmBy8`!o}tW7*yJ!F2t+%O0Tq(R(jF2miuLe zosBB{K7HLR!X+9@qM<5L5l%FO6BP}KhK5AN%0$D;L`74gp(#%ZGN^t=AM ztw+DhU+W(a@He(o{#yU|vVNDp)<5>@clm3@`s97P{FO<<>JmN?*V(=+7$SDJ&df-} z?$KH0wEi`nkumDNTe8W2+}k_GqKH?@HHIhkX?zjghc#t(IB`}TGb_<(Fsl-c-uOK` z$*xv&;7I(dG*TP`*jFj(HESMOS-a#H(2I_`T{--%*R=A_g}k$lm+jMRYAr~#HRW%D z8jhf3&bg2yij7bqq@gkk2@|5al;0Wriu;gRJhr+t(pTOWl1>om4Wtomgq8fR;YI_!)5Yk0(dg}Y7A$8-!IwK54g{o!T^+H(GE$x@e zk<8mOsngB9?&|1^`uMTds8|2~8NGqqX6-9wJjVPZ1dc`g!fxiz^D0DtZQI*VNpK@w|r?P`?HcC9vvPW z@qc`g&JXJph%cyvoMP=Vw{;6FU>yD!j0}FcA)zNXSOyF-Lokh=;M$U%UNRE)92fl< zJ;TxEAYoW;d~N_8!tP4H2>uCr+0C%Z)-m(|2$yLp$W{;nD;A9;Eqb%j6+0y%e&ywm zoXA?vJ-Og*FdSI?bArb9iBJx_(Iu858Fi;L4#}K%XRzlca#m6mh+AjKSp4N?!^gHVr96#kERBOADfW+Mok~IEpndN=gd7+^C?zx|L z5aQiBY$DqUOG)E@PuoROtd2@=c}X6NS^J({j) zG+k*L78jXfM|iy#Ipy`n8@u_z@menzp4gj_HXn-E%AnU5(alwT*B5AQqhR0lh%iOw znMsRPXyjs&l=fX8$Mwy6=r&zp|z_ zK3~fgeqo2yZ(2-9snA_N&>_MoT&1e%TId;%z5-RYuqq?H4Bqv$wQzcG#}lc@AO0X6 zHovOxqQv|#=IM#~4Va?;rLj+ZeV0zYvhQZ@fp6-&xgarrUEj?`r${f-@YiKyPkg;Y z=h@VEb7|r$Exh;LT%P#KcKs4OWlnE8=eK)EglJsPB2nD3jkPAwXMQ`7H*cSg{!M>- zrw}`Wr9Mf+@X@>#bo9(A-M#yz+3Qw7cv2Xp&5< zdeYm=U2~8%n<2jjt&=B&Z?X6D9sN|5Q=AiD>UxWX-ZgfA)Dryf;a|Rl#O7oC%SAVz zl7IOv=tPbEGw1Dsj}^J?$YE-xkKA(7w%!fL<6i2liiJh8+|~BFrbp!lrQ&B!q67AK z4ot(RTC-bNo}1+uE=fC*=WuS}G+F$bojU1+k(i+xe!k$J3bTq21YXrAbJ3^NXZ*jJ z&)FU5@t7B|sIAU}Dg)&p=kT$kc9s2z1GA_01j_ZKD1Q#x@ z#i+oAP>M6cHJQWvWvmrZk=x_1sf&MAI%jb`iQKA}1tqyS_jiwu@M5WsffPqzsP~0e zFPu{`%%l@fO-wn5bqj?4-gdoBoQJ%hPf6XJz0P5g8(>FYdFsQww?-|rGwH+p50=mr zj_BB39V~t+w#2Z9;Vmbce52!lld5X3$84p5Ox5M+y~J2t2V1nJR?U`rFQU!9;%DM* z(&lh_@M)Y)2ioIbd|WuQbQKf8p@wYUF->vk8*_&k`W z#m}EKpKZ%Is1G00aVRO4eJ3aQQ|H^$oT5tWuUVT_%SQePt^NFv9;MsmIOSatD_y?S zrl7^0!*Oecy?%z0ekt$d^<#s>P;j1g{YTf9U6;V%h9Ut=kzVU|BV13pb?S2;N;mp! z{1dy~0RKSX2)hub9J**AKj9NjWX$X+-2wJ~4A!YR1q#?H8?3F|!bKyptJq>fTg+IX z#f-9_l?j8l5FH)aacvD!F|m_rMBoGbEGEG`HWsWQQAy{S!BfsNiznD^b5=$1fmcEC zyg6dF&jf^50+xvT`0?|oyw{+xx;6mM}%H23;gS<3EriiptfL4G&!Y)+3xR6ABG+h?7Cf?mj@J-~pi1D&|s zkosqD+$2+W=eYV)d06Ih%}w0*5+8ol8|}9OddDp$gF0Nxu|**%U)oS4ZOBLKZCo3! zls06z;Z#6fNE^5?-4_*p9$M9Rze)3?B|A|yyxs-B&8l~yw!|&490R=Z84DH@R%3sP zWT+rMLrV0A391__tJ|fX!BE|*_A`B}w9aPJVoH7j@L~1X`;2aDVH3mMcWwu~1apr~ z=S3R`7UR>53S32WS~`SQNY{&po||}ol0>TEU7U(J_25FLhVHp;4N8BG;@nYu^M#M$8@ZyFOJe-UKC(=_YscAP} z8bsqk9NW+8yO5=iDzR1!jQbOnMSW}VW~JX*7Kz;6-*NV?G%(CqF5E24 zGB|wqLftzP=k!$;h~fb=y|1ze<%98t?3yPeN-MHSwRNDF;iihZQ#P)YeaBZ1ewi#} zQAnehEv!w}-~k)auspZY)A3nc^xd<#R&d8PbM(*@AfTMVE8E;9c1Vd$huG-DxBiD{ zKrORn_oMm<|4e^p^byP>!auzQCT2*Zs7=P+zj?{tC&Y6U^)8}n1x)RH*#sV*Mp)Y7xT4hD4V4kt4r-7f1(WZsN@1f<45BWEXsuukoW`MJAK_3YcMS71i0K=FxvZf19Ao$3qfs;?7_z!~8r z#;a%?k}sowB)Tb_HKxZ(k=g}1qwfpTg1QO`V#|g^a3VNe>mU6|*Yp(nM+O!R!bJ_1 z0<3R&sjWJjYh}eQ<0>`Kx0Op=y*0CM#b{h^>}uRMW)ZHltT-vpDDwm?FnVtCirsqg zZmZ|u@xU8$IPx}MqUEvo3J^A*z8llf&$L|k;vOMhq0_&6a5(UW)q^b^qY!id)IMg7 z;urIXTZ+in%3^XpD=2;+itRZBL!HNwbk@U=JQ11rjbkaRyX{5mgXsI{DBXz_-|g`m z+GNWrw8R&EZH&2SYf5av%ToiB8 z_j!z}Q`b26#^-5(K0>)*D6k);QvuIxHs3;T-Xn!Y|Iy|}jSj=uc%4H2bPbb%nL1wo zONNuHq7iPOJRy=-bGT^B#^5(<&EMuZcZ&|0^es+do@Na=WY@2E9!!h1;;zZiCRC$9 z>&ww?CG~Olc{L(tL%ZW$AxsvcI}bAta;CHR?c&`_!s;~%W`C?-LK@*On0tZ@!ZLI> zfliEf@ej^;Zq|q_t)?=Y=!)6vO=VIYr?oa`4?TTj~dDKu<-Y| zkB}Wv&QP;KmaL=hlXPOcD>X*W%u#)$AJg|boi?HGRcoCcLxkp95FJ_?cQNNO?C^AZ zn01^;M1O;B>S7eWQ749G@fl`)ykdm<;Rdf(g~5LySEldt@hz?m7mIw#_5-UKJ`!+p`6hcsB&B zv#jjI+|s@VyGQRV;4@g7>EJuhv8G$ymOoZ1iyOKucDB$km`NR2|8yYg-nhWrJ7S&3 z>K+H;EWOxAK}@qMM$7?M>@4h(83|EjQ7-dsSD=^as!mxcxQ<<0GmvhmVx2!kYf}3M&uf%_LUqai>>8B z&T;2pd=ge2*MP{cgGT%*FSY7N{ADTEsYmn+B!HV%Bb9!di7VuSOxPWE92zs6f8i{^ zf%vHYH}3tctW?418neGwx-$XHUlHpVI$Sobv{B3ARM-WX_G~)6F`AyVx=(O)d0Sn4 zgDWr?Y2s>o3;%bc6X?r6lxZqmk-0=(BisdMck)u)-8{dOd0;1GknBysWgSco1YU`p zNenlg?TXgP3h7!OO4Z4@i9w;{pN7imdm6@4CR$0mZvrxuNy(b zV6kYbFT8R@{ZP)mZ@cWodwitd`s*=!8y*$m~f-RewX@xs+1@GaG(1NWoX_W`$T7=^?wO!){MB?_1u~NC;ST9fn@Q=H; zh&^DD^x9(5F0`khUENys+{szBy!??MJyunW8o9(%O{w z*^IQ}XP`lTrgZOe9#|2pb4$mgP1(r4 zWb0D;tzV0#W_IA!v@MXPsL`Cd zdpU4}v_vaXO3G+bRsk%nNf{>v)hnc_CAKEzQk_R@Qc51Z4Bghdfn%Q5&oF|u@WQZY z3?w3xVN;22r&Rja(NED6wpzkhuF{Q;eaRL3k`eoolrAz%SX+x+f#;YTe?-IUOGfcP z=by=VdzD_`GCC~e$uc(c(+a9SKrVw-<=%yLB`vgpY&D97%eoBQe{#&2VwF~7K{M|5 z*<)d8WvhCa82NW`xZm?S4M(qOKD<$JufwFj41JbmOJ#Q3MWI%MM%J#G_85x3TzX=s zb>>7C^S{A79KOz!2~`g?7e^I>e@`a@Xte1WY%TiOx52jrkSO2O7{#y9eg7?eK2b-N z^GkaD!3pd+1^y_&bVevCcYKj+`s>?ebA>Qk%<9ay7PuHTQ~&OLiJ|wDvCH7~rgL zlHh)GPl*V`3vKe|e~+e`uK5ZlrJ|Q~?r}L~)-ykoADf>D)YewPHrfwsLADiWn6{2? z242bpu`o;J{M~}3x17J3!+O<73PxPqvF5XaM2Ykcqxb}vfS$Y<7s`4y1wPnto_JNx zW<*zTr|)vWxkhW{6-0!8O3?9QSxU16uQSC*S#&G~duOxPEUkCTT7rVGuwB3a9*^nB5f;uc;ke2f;}m5@YdDqZIn1djexG)I3>y?ZfYcKEXvtnJjlKY8Du;)-&9H&3if;1~v|(}lxc@BO zJ)$E3$Uu%%(_^lNk6A92Y+cG5r-6mS8REGCLBa^_;(rOA#S`S2$78!C<(dNCBRrdU zHpAYP39e1Kt7d3?H-@=k;~KezsO1jwNNV4giX?fR-I#qRyWm>73wDSkYd8&n&jI5o7yME zJNn0KEZrq-m+m@sjW>WAkY@NjZH*i$D7rALZY|MOFRf9l@F(6_d+sj1m~jDyfw@^y-H;Us^1jrS_HxA=~@KG*TT10#m^b7g+HvOeXJJ2zg3G7 z*<3a6b=qhxxb0vJDO9OOYC#RG9fe2f%{1n>`AZ;E(2&i=7FDdYcgY;_&CJ|rz~$ki z%mKnX_>lpTPhlDtfY(-LQH~&+CZ1b(*6~EZPl6ycQ@d4rucTBFhVJ5r$S3*n^Qf#} z!rktQifg@F=(|;P`bwGK%t)EEEt2Ms|3&kv{TQ#H<{Upw2sMv%?=ZX0RWkYp| zbA_jFOEK-afsnhl#_~KYXd8ML8WKst8g|jN{me7!^ANw>9q~R2-hsK|)6(l{{Q`ZG z)UtI8(^U~7SaXAj3|6N77ok%n-5NovFu#-^l&M6H!P`yj`s<`~8Gr)0Q?ih!h^K@{ zlFlGOSh^gC0dj>xQ0NI9X%Kvq^gG%@(6H;G9w19n_CPVa5+5%GvXpNStWc=_;TMd~ z-spOIT9#-D1H&E<>J)J>{sGnE!wd~rn~0KhcQ;Gq8srT`b3FqL9;i3Km&3FX zQgK$8X&@L%h!=J9B~%rFHEJ1eGJCkvhfa|(*@FSshWYB`ASrWQMpESSf;zF3N5y7yIDosau?WlF&r40Vk@?mT)z=axqMS(_$VwgiIAf75> z5*0;uC>TY81;d4PcxgJEagcBuY-aeLrQdvvVcf<2P?!eEupradgMti^fm1gM`3bEg zv(*|#`uhP`z9wUy?q|r?`}3)+I@?p?%92dxF*|RX3qB# z*EgBBIbJ+>6K$;n5Xu<``#jbrt>-oC_!|Q@II?2Fb3GaUTVVYfZ2lP70#P6P>tM}} z((9<_->UIZ4SIMC^vK@^{Wrk^6D9V6H#$8wRe-ctlVJIQUvF4b{Far_=iR@f^YOrR z-G8H}M$3(U2cKV11)w(D)7aAV-bXM5x1KT?d{+gl0WJZPxIi{R46WGptG#_I#h4-Z zkzk($OG@yFomh|t<_x1&S%$XC66_+lYt$;MfHe;4z$%MiZIlK63ldZyw<7Ut<2CJt zY)p?PTU%7wGdxpYw>{BCge;4r?e)6)jaNZMTTz&awuA6)m~bfX;ZOY4w7HA#g~j!1 z0z@DPsK7+Dw3m)$iA81Ec~{uIl@^4jS7chgy`_?sV$?2)*C2u)wmxIM7Av-Hbzv`Q z-72P&)~#-ADXm+*u`hV7tv;}>`q_wAQ}BD;AVZ-rSVBH}e zG7By4hvgD8lzw2P^m(8IOGtzngjfvHa9Of)r@iN%%}#K_efrEqA?~t$bQgw}q2A{TGo z^I#X@A(ud`HN?GsMAxKLY&@ulJvkHiX<}YeW1hA$&=tPu#zq4jAph3Qybp(u{8QjZK(53B$2eZGKwsCYz}1 zX6uQ<7D>@1&Lt_zAfS~1Dd-7(fQqe?`>c29FrRLdRBkXf+1gRqBBAK!*?P<(FtXV~ z^b27+&mw(}PPdW)#L2k0NtOwMB8XLLy%d|yMig7`vhZ-Zo=wCZTkmEokx8`P8=Irc zBx7=&br8a5I#vA}y+ZHlT{=h^UMb_RmH=o9p)W+t?mnq{Ql6~ z)ef7>;}wp?6D&Z{h*h@}m{!oS@!zh6Rp1M+97MIV1khj+tc2!*Zcf5*Jy_SQ6&%Tf z4#CSD58*yB8N@tQF!r^A0p|GoLgTp56%j+yF^O1Zmq{Lq*Lf1I%f!5u(7%?`uXDO? zi_g0aYgpRuPRzRv$0oN)CO+lZBnq8c$N)6EHm9zI@LpxX-Uy^{IS^w%Cw)Y7=%%2IAwgj|`HB@CjS+s0E=>H5N@4gprNeg= zhS@&&+Jr$XGif0M2TqiwyEuW1D&A%0!V(J;!%qXr+3yp=a}(OK2-2UQQVs?Dlyf40 zF9Q=CHh+z}Q6x0?X$?^mXVx!nDW$-b0J87@$V*fV($`L|WbgD#H}y*=Rw%m{uZ`tJ z`^YU7Bx^BQo1}33*xR`ZKc34Oyf)?}*EMY^ed}Fxf*C-QSy;0U-lDn4%#cc@7sR-| zR9-XmK>_pYQ*xroSdwdcMF^4%!6FM|j9~eD&B!t9l%YDL4^(mr;#|jM=78fa6ywdm zZA^|ef95Q>k2i5>>y;x1>rJ0Ii03q-ueC7XNDwSs2$?;oQBxxB+s2*v?DlRu5}|jH z7}dpFwRl4$M+|PEZPw9Ufhsp1e(e*ixyOe`cbko=hg*mP`)q4(!2||Lj(V>?ot*A)x%7SwMIyjAfgFm5U=uz4vt+QBkmrI?bY!@Rr}WujrK%56X`{8*i)l52y) z)aZT*wjKG3$6uMW#554|pdGW0TFBNe%sd>-+R_(tY$Dw6X_XmY6x|mN*n5Aom`hmn5;pODfLieVR}EnuSh^d=oVI=My^k!@Ui90r)48< z9pkZMhSM>Hl1I=m_Hu(P+GxJHN8~>J#1r$F{Md!4U$gt5Lo{w8rPom+yRPq(WkZ<6 z_kC7O;`=`9{iy9I6}G4Sp+v83E1Hw&{qi!-L+J}F^7K+&-jxZdi00{qObB4pmtWlZ z+So@$_dI|C9YG;NtM&V*_X#jCxZ5k-E6h2{O7=2#C`5 z3b6nc!>snV}N|bBv$AZL*(`fuS9HZf910Dhe zTE+Ma@F#2dki=sJ)Nn<;hB_K5<&A!%%dmuhQDwB(Olf_QEA3N|Ea|U^?H^O(Gtr{| z(V6~=ystaR%4!djHIge=UE+4aTibr4^uXD4N_&I6xzV~xzekS7rY!A(W3Tf>&l7l4 z0$%BfOkm_~J1#qxCFZ%$rr}4cq4(3E&#|&?$de^M_iE{{$onV3K0EDC75HJ}qyqk! zhHQ6$Za?@D|DadW*JwT0TYo~|bvQN+E85r!F^P?>Ff2?tSGc*JAjV$0QAlOv?6>=( zFNsd%xZ!$MkC(ucbC^4F1@O!Pzp4Cz{aTOqufr9P2TlTM2@f5uP_hfWtAK}c#)W?$ zEFlD`>Hg@mqcAnR3c2Aye1u?VAd*YZ*Yoz)Yo9h|FS2OU-Wu(Yq*U8BE`OJ)+;XjC$tM$Ugh2%_DcTUzRa0b z#$z)+V&_k3?Lf|PEIN(jwivGbj$^fTMZGeh@7gP;n0s6#I1zc1mVQK^L+rtW_ShnA zq!;ZT{M)0IbuuIlnWBu++(0;`dC&ZTl7BcW4eYP9AnZ6v@xCAG5hpFnvdsy_Ey*pAJcco z-<3;nhO2$il-7OqLL5hL7LH4~b*|K1^qlipz|{IzK(ih;dFAn7iz6w zsdqHT+Gr$mk;u8ND;NRP;vSLOG610Y%ow1R)}4D)+PwumbG%^Vn{LVJdP0-psa8_^XRKl{YruxJO@aeeW-O5eY-#f1?xL`viWE9kZ+(j)lOgC~gu z@(id*KioxVepJZ4cnpRCf~GRT?vDhI7Glf0kagWJvM$Lwdgn$Jy5sFt^j}?M;o5V` zhMGEP21JezYPm$$8^I(}NBBDi+Q{JQ^*dR8|I8S>fEfLS8rEc*|+Vu%h zsq7U+W)UcRRlc0RoVu7u4ldx6XIZsI`?ZuB!T67>en}X328K)YOZFPr;9_^dY&qnb z+2D%ipe~=BIP<)yD|U6#iM6@4%w;(PP;b#Qb$X!eO``ENLywz_LjVb&0%u-lL?d>J zJdXc!jpUko^$w&r3rW5jus;_Zm;ofpDUx|ZLjh^o^{nTp0*UDZ&kYjcep&QgYup# zU%?&c|0S=vDBIu6Vka@quutFKfZFkMdn>&TwOv$TC4ydxZnV7RH+rK6+g5p_H}Vhm zFBi;tx8LXulOsrupQLjv@@}v4ZbzaPMiBTM3DhiNlAG)@ri?42RdVFoMQ~@BA!QU; zQbhDD0ckB^+jm(fP>$S)Qb~yAn7qu6_mO;D*{_KzZ*Kc&(b5bl`BRjzo!x}~2&*~F zC)OvO-`25W=|;?tSgfKmAZ#0X3y-^0<%V%AJrcMuf+D9Ym-n8k!{ zFv=xM^+LCvk5BD~b zQ+jn8vN}bRph3NI{+Ql;k*rQ+W{cS832gXMEgD2p&|Zdzb6@f5>~Qk^XYds|;`?~ zv2xjDymW62;@*{&CJ+swrQGTl@DxC{m>$v^wA@kGd`5kZeguzREP)U!cu;{6fyVSR z>WE-s8LF6Z5-dW*iwj{6O@3yCUb6qWWwWsT$B6T7+{1iy+Cos;-eaa}?=fT1AM+if z`Q=;$?Ay2^?mhrEbc?Yfn`0UufpF@rEv~jy29+4aFN`bBMkO#5ucoQRuYPP|;t{q` zfXaX}CBt=?Fw`sY=fScwyK%OU-xyJ8=cvjKtlh?FFW#akuVd2n$o$l3vk;E(XtfD} z3bi~S1c}%cJO_$^;>cJEEEiK?JH2=G0)QXbX}BREw#66Q;+NgUh6Qo;y!uuK*0xMK zjK-+qs8un?9jzGPV>&<0be$xJA`#(D&6gL@@uUJB;*L!%)FIy3q#_;StJf3)v&35y zzte3!6PsE>L~OQ9XSN7A4y4rU^o`{R%yr>AIOs<3$()rAnhzya#~=)W&l&UasLCGH zCHk7M0(C72n%R{vx`A}%GfL*3<#&Hl(!eIR2CX+f}?!v~ay(Q0XoA$K zucNOI;N{vB)JS^k)Y~xU+d3MfIqD#V)T!5}=}2 zXVZe!BM!le@#@Fae7^0&Qs}X8cjz&FRJxzd;8{EWSJL@Q()n-yNd7#@udjiy^J`+R zLGlmO)7tK=AQ=bFnkbGf-c?wcq=w)rW<~Pq)IP)>jW)$xhw%?r6R7`1#_n9nVuuS# zKH?q9nZ>lrs(VTzqL-MH^k+OY68>4K%*W736%pzZGB+LEgKFgE60ADui^e8-jaLt< zg%W#Y8Xuv-a4b5g9zSiAlCk@o!s^8niR>b17j#+&oqGc(He!V3xoa~d!Z9sti~4Xu zZ2s119yiv1nk%6Tzq)x6Dz@D}7a@*0;9BoC`<>37RAJjrcZDNW7~etkPJX@e`ygS@ z@(l8vf3Q7wdmdNtY@eUiUYQNp?enwEy-u@R1AlfDIJ~yev^rImxi{PF&Xy{Ce>Bxj zJB_(FODfo%C9&H_V}Y@O3asR5;0g0o@dSCwc}jV#dG{QS&Aaz7zlvYQ?-72F@H@!w zAiqcXJ<9Jezlgc+;iklUN79bSom?!P>5Y^$`aYfqd7cp1A!GT9eO)`H#pB=Y)~7?L z<4HY2cVyDWBbSZDH_seNk3r$s7)<)}d*2(OT)&4>QpXO_(>;@67QmlOkI8X+Op0Yp z@`)maB;HxVdzfbvPkW{F{Da%)JI%Ls@4cgY??1E7WHJb}vj)&*5Xd^kQh=A9Bn?ccn#OrJ8+NTIt62AAX z?YCvM4n>x5SuUKR_B>{O`GLqMXm<&A|U}>X8)g2Qh@8U z%9^bKFB^#kR>gE-ke&iqcOMMW`Vs0;))5ZVgCnV^FBSD_h=%%FskEkmXrWd^BO=}dWQnMLM-?@buW8J-*bdNB;aGAe#~>|Y#J2{DJzs83mrj0I2IZ-S05$$ zFwcl1w)$x7i^HoP(j61(Wka=lvpe)G1<9(4g${7GiiKW|hYrX=E>)_wQL9uq(#WVj z>oA)~9Fb3q4u-X?H|9+D7EJ97JS+6<(tY*-j_7VS0y(-DJ^@JS^d7YN;0QuS1P4Sc znhx$?6T#}w-5o5H>JXV+yEcn})H=)s`O77j{FPoqk4|1007LmdqkEqKb5o%sI*~BO zMZE|8A!kGTpKQHN(w*vGH9^FAe?-rqeCrDZseZ~z*Vt@!qvj?qK&;!{796*|3~MZE zY%VuXq##-rO{com-bHcOPvS0fW|gZsCs1W<$&px&B}R&I(isF$^D|ORwXZUE8Fo9d ztiXKt?KsESn4|IlvjP~)0Yb?#Sv2t!%T-?5W3_Cj2OtntHea#F;h-hse_UN+9aSeMZKy+0`TUrU4Q`Mu`v**!TZ7a%4Edcn_Q0Q zyUPb|z06Kr1<9r-zF$u;bG4$?OpigjITkv~<=8;6lVd9T8^bsUiMaS-k;Nk<=CKMFrv!(V)-o+*HKB_T z%ibkaOP3502h8x=6HNvHR;Bc6Pjmc;DX#D8!#e-}T$qDHf>8I-q?sP@xvQflKx*rRe8yGeljZdutXU3cR-}_!HG^~4bBpx~n zP8kF-g8oudT?a%fR!|S)veM-+R~n9P$9A%H(P~5#A|;W})Rk&Kl?#T|*XSyU>PBWv zWJ2o7u=)T*^?oi(ho`Au!~suj!`*@ilrb4Zmu-KvzEODED!3NqK^v&F2zHwL><*IIYe zBb29p{7GV}52IIL05uqyq*H_rt5=C&S~rJyOaEKGlvH8X}9>qdvruUbi+0#7)WtQejH*rZ<|6^pA-*hEV^wowHvZ1qeIm zVfDjlx&=YD6Sq9-t2C94>{@Fy^-FR0l2T?*FCS|stL@nA>sBF_;Mm3q=W;pWXyCH= z)Hek(34h4)YLx3U)qjp3)1Sc$OOL6IEQH8NW>tEAf|tsl;BY_=dhdqAb?Q?bry9c` zhdTVYQYuGOcoYy3c+Z}8F_qf1Dlq$jE16Jv>Q^|`K#iIDn_G*rfVE}vTKwXwZv&9V zz`(k`%JUOfh1oBjmAEjp*YlIfmFDqFtb>sp^LTO8CEwVe9WUKH!8|^5YmPZknsl1` zxYR2ZamQUPaaV;TNhZt>E?KcWntiOdYhVKnqY-$90=@t4A~+Ci0msTZ{`Bw14mqE( zPH@b6@B8hQsj_`n%}?E)LrDYK#|~PZOXZZ1J_4JwpI8JnB)sZ#F!EX=G@EXsC z12fimwsfrV+>leMBR)8=#`DttA2iMQ z@m!j^v+(DCBnjtIG(6qb%jRxT+ZK&zSIk$a_Lu8frITlB@ZNq(?p@>A-I+Bz#n^5B z*_77Io+k z4(&Vio;f=R`R(wu%_QH?1yX#{0dVrb6@1@b&Iq`z9;B`w$3*s#=tbM!BuPu6H{v>! zOzuAPcJe6|2YT|HA4r<$pCIWCM>Lt}ef^Tb@;UY%G+M^5Nja_z^#+x?QSeZZwyH}Y z9a#jdrUrBNW6TC;G`QBK&SP1p@y8WGUO^zt-P2eNi{;Z^a`ZD4)?r8VTo6lg0@v`w%h!gr2*c)8*6XsrT210ixFnf8I4XAjMz8VhDF?5c%e$IdXueuy*IOrzy4Ly|y37KHuEoQWlA6=OE2V>%VwJ9DUdPaYj6n)2 zK-SFmVIN)&tJ_G_rSeJDrMuu)q&e1mPRFs{#;Oc2_z~QLmB{!AQ~#vq`|hhp#r$aTmjAWcr;S=&_Ek&$fo^Q&-d~ z4;cT`&Bmvp2jB~y8fu?c=kejAI}VgA`^R|PyMUpvT0bY zrzHfvx9s(qD_pVY(Pk&gTKIRbQSV zZ}DqGozB>@;m9lthmV~f=2-dPYN?*%FyEXOckdgTXSrG;XIT5;$WLmSIU(vyg@!8v zp7rlZ&!L4B8XkCo;c4Bs>1}mZiR|!a@@e*@26pi~G~dmw;NRy>U%VJKK3P3H@O3_m zcRM>pT!rhroOphl6lm==`=`ZcbXd;L-)9fa%cb14a`AgAdQ^QmY_}ye5Q=xJBPY0YN_ z8J1Iu;WNd1$oMoT8VJ|w5vSaw0T;mC)FPubgZ>se{$*O09xX#PGf1PPR%VDoq-2N; z^`RuSIm1Yz9x>}9w?W?G4=ysnOl7gdrm~|e%>H-yzziiisZL!2yev5Hjb-qbQ!o+8 z*V@r|hhg@QkR<7QBrD>5#E7_u_PC;X-Iac6TRkh%C-e2j>p4~Kqp8eI&sRGaSe?nq zsvYWMbU18+a;LOs)hF!sxW?L(A;Yd^3IpY%Q}2u9(Cs>3x67P;1DlfUTrTFA#tN-e zpee<`rl$6@J%J3z68(mu(1})L5~=$t=^rRkf763fqZa}DtNUb@bgTbF6DYP?Sw~}6 z*QKWVLDSYEWFd#awXE%j2jv&(>C~h0veCWm_o=PWn3pR)x!E-0-uAqsB@@uuZ#Z{9 ze1xd7RDEiy7hr3)l~>=$yset$?AbOm91=E!=cg6^*%Mh3k!iCh(yfu4So7iJMdr_1 zsnX<)e=6&k`LkhOlatLmB9k}%R=ySAp09S$QxMVLEvGqbItBs<7hTw>5|G9^z^mSq znWDb5gi1A!sH;JwQ2)l-bJUL|A~n@VtsdU9oNg$(!Qps#AziCB*QQe$>Rz3_oQ~Gn zPE%VXfI@#r-I;-Xf$m6NST#xLL#`_J2!lW2)a4^IJ9YUmf7O;8J*-#^MSEv9ACBhM zsc$d>>L>h37F%#s4C^#h0dS1=1;&Vxu^549zuvM*+$@Rj=Z|c%*53H)XVr~UnGz2* zP+5?qM}{|bfZZ}8oDVs!e}o>==iW{^;6@7Dv&_ycczlbF>44}va#C@m6;(6(s#!lz zoj9?@dB7Y@mF>m>+7BFAS=%BCzn$cq4#%+Y2h1u*kpqrs?7T3;9Cd1s8@bQ33 z|6i6bY=Ui_mM;|XN}pxMWW0P~Gj(AsB=OE2yg$a%%af4_oKn6ZsezYC^H<~x8t%As ze_OtghFwAtGk9k4%;QNHva?i1u4u*ZRhV!o(FlJkdVyS{6CQ|u!7d6 z!Zu?pEJu(ucM3Of?l@1_-uXOFaaP_dRLJn^q`OjoRul;yDUa7uXsU21%o~m{|zIZS=(Yuc;BT4HiV?oOozBtUd?! zg=>Wj0KOk2#t2$%`?}&Gu0d)Yi$dXIUsqeI&KivP>eK~nR>5$c^H`m__IH9~y_&h$ z((Hv`9gLjIP7yNdJ>TwNbH4f#&wZWNFemO#^$RwM6@*w_(cHbxOX730q%K>g#H+H} zr)Z_}e}l4N%FIIFoc{Xq^%!h@xzJrU>LtPrF^g>=BBY>-uVIR$dOrE3?AzADUmLF*FLd#NY08b~$@$)VJ8Og!=N4tWF(cJE9BC zJwG_TyD!6KB(stN;$5%Z9~l$9(zLyiRR3Vx;Hyxu&{A( z*QF{*SiiQkR_&)lu`e&uC{a;y?9YC>sXZTW1w5ZQfh6zx{5*&MVNc?s{(_b z2RhB+kerdVbR#+l(kv*sEE_;5LNB3>$tfoVJqB!+z_P9;q@3`- zv7=JwG4jw8dYa)fq=T89ST>9efPNWFga-Sf!+q7meP0|*EK`Y)>N{85ili;pSgre@ zCiZnT9VWd^!9j0KZR+7OoSK>s?ZkHu6YoIRz}Kl#n(m0tNiFTlkQCU@mvyvribv%f zk`QjYacsAyMW(h-Fn4E_ABwy{7uMK;(d5M5daJARciy^*z1D)SO%?-p*wDn7tKAMcZS-WX`GH%XI6k%Qgm8c(#uN9)+PsVW#ls7@9ej~%%cOezh!>I&hwsTU z^TSl+EDJBuIhH%FPjg*znsar;UE7j5y9#H{aSR1r1(8W|qN`OuoMSIOl&7nW?MBka z@@734fIMigOQ6ndcCUbQBPVBsV#Wn>yhxsA_7u=C4w$lPhbmx*=L*w4QkYuc+BDIc zvOPNmXSE~g_B_=Ad!>`f3lj?AsPnYku2in{B{+yX$*aBXTBxOd%Cs@BP5}pOvh@!j zMUJgOjj0YrK51@+VRnw}a#^{_v)i3=wGv9jcadqX^AnEPFC~Fz z$2wwKJ}lVmYx!`~R*&bYF3(df2blF{zek+IdY)?S9OQFtUgxl@5i6|FPS00L$b(|V zudd*(vktSm17^;BvCspt&?B+Xqp{GQSm?V025Eq1s)9(sRL;mHrZOVas;VNV^Tl0d zxr|Kp9%G>2esK-FYQJO+JkLu@^`4f2r|ppJfhQ&8!;7OAnQe!uw9C>zR&WIQOXv|# z`~f?m>)5hK26pmp5%|JcQUeP#7@9u@ zrek1+&b=UVY0HOAk%E>FZ;71V^5N~CwtNY%e%cr~LucRP9hhLh6bxkX(w;Z#is&a= zwr0(UPMJTSge`XG4;98g}20>%4{;tFGldhq86QW@4t3DQj)57Z8DID*%8RV_{3b6_}dZ7EUs9nmAOE7wQ$*I zbxUfh==fO8dk{Nq`vV<;D`^=FBzUQ*qU6&k_2HUR9Uz)OjV)JS5;d3!S(OY|omzp) zX5&CFl`$1l`a#+6RgS0i$H1!cwB9E_k>!FOT05DIRfNeMyBc47k6hiM`!6C*GPGcg zS?-AB27~yFf3G<7P9N$DM)G7b#Ddy@u$4;6ER@cPtsLNda zs3ZR4ZmPg^NL6=0;^s;W?$<-RzOgvWO&XtrA!BxyBJGPU+ab`mIGxq^Z=bv<`E0yR zau)BcWSVBn4ikNnOIn|AnOPd8X3L;!0C--KR28lGAAAm=FjLu@gNE0p`>P9d^ zzh08`4RzVC#mUo#y0Rk^2`!+jfez98NOAPh;^?lSE;p({Kh`KK^hDj-0`(&V-w=kW z=%dyz)4`&~`V_%KT}ERBu&$`5zHV)4JoJQO50=zs^LHJQYt80ejxFIqPu9M6i`WU zBV+E0oLtQbnSvj5L?)%852}m*i~Oq}L`I|c+V*Me#BG~N#jSwx1C(Heo>;2BS%q%I z(=YS6uPf`a3de1qsc_uG^BT`Nr4^1sp3m{jCGMdP_;)B;uk|g*=w4W}$=tx+W=skn zmYB7u8+?Wq31WNrNrW)b^VYiRVwX#tI`gE6oV8~+Ebl6N@n?Q;N;2mmNgZ=%o1Fzh zZyvuNov6)kmF@d^5z!d+bV6lyp2)Fg{8)%C=q<~2Hys_3@pqaNQs(Z0iftckC-LTk zsL^#P*BM~!+4-;tS%CvfC|jSBb#buKKQVg~CEV^U=8mo$vjbz4tKt2^&Fv_F+%ACJ z*2&FbU-LvAJxxbL9vL4=@|PiAX)}>E#KMn5^y}y`h&qW@AremaL)YnUjI6f_SUJ!q zC#H$mRP$YWhDXTHI841tSDMgtLCB}$VlKK<&1cxZ*8{R4v^b` zGCFD?$w}5VXzp`O+;V?xxogd~Megh=s4OlGGAQ()2nZdKPia%+p~^|#$eDGj2DmM2 zCcSO0@jJ{5(c&;1jp8<;scPn^1sKhdt0ug#N4&-TqT>@9hRe+{8!bK*?M3d!F>lb; zFzT|Z2h(ckjUtMu>8hJMy|iI&X{kO(;bx(JiB|Fo8OMTJnaFm#q4jPM9HDnJ9Gg30 zZE#~sTdO7@k2LqVCU!*b6t$t|xO=08J}TdhbxY!3Kz3BNuk6LLp|Vu!z_R6>5{bEH zQdjh3q% z$gHmC3c-k%jUE^K-9CGXML#u^hjd~n*8m;DO|s;O#3%PcJdzzThH|r`PEKaR3bGvA z%Ku@*7yBa;pl)R^F&`AJzhhv+L{9YHrlxF`=yY})vB1J_FuEuUNR=arQjh>5IOWPP zUt|?syCo-ZyK8ffa*`L(R=*RI3uljY849F~GML0+-of;l8rxtrIr*$5J{8GwsYzrI zSeQMBjwtR8O$i4+4P8o(_EU25>srW-9MB;p=BR&x{sET0-mXh0JFNZ<`rh27+pxv0 zzQvbaS3^`~TBJ3r*dZAVy73&VO72C0(qV%danzuWsO~|xNf)z;Wb{#a$c>yssxxp5 zIhXKnvYdOR9h=b@b6E=vYsPfTJ=wY6*@@CpuxY21A$LfMqKO;ndTd$0xq26-D5#nC zq&E8FSSP5%ugbZMGl}{DGSLcdhB#91$ZJar?Sl?dZ}Jsew^<#M&}wgNyF^Gm(|wtW z=EHt~*Ws&I7x&5x@rnKr2?qXylp@vu4w|Ef?J>x>pj*d|{=&Oe`p{;Gce zB=4eoNrHR|knIeO9bWhaRG*fJRQtF?Lo`Wg*L+@j#R1upm&;y^EqOLj>r!(6wcDpwie{4tGzIE;(SicJmUh!NGXFdQj*TG@fK+M?}p*G=@*th4rhE z59#|k$w%xCw4hbzBh}oaj=e&!sUA)P(D1RU&FYu>^+~&Lwp}e#IeN9Zg*KL3mA=`! zg?Y1e<1UgtH~LAlx!(~vhhb1L0mdwttOgkjRGD6lHxJ@ps1KctWaGo~!5n5iZ9=lf9KwP=p zDyMic=KA?)$RDNAbN#Wr_##6+KpnUrPmVOQU@O(e(R5FzbGD3zJWfbzqmM%B)&A$C zKi%dQpUczsZ2_4l#eJ2x|+!^GFCIWNK^J5%+H23#fqIqG-J zXg%J(5A+%X53#)NClvh7YMjKRHmq0Fdhia+i{^ZhKS!N)Nhfn&y>}4&aHZzNVRh6X zqcq>u1hb7){vhFOXri)vog03np*~OPupy~u9!fb|$*j4ZHCSuGtGb%Q6l3>&x=F3$ z-P{yG44R4-rlJKI=AKB0>(n*W9o8d+#b#U_!L1pFBpV4+h9p$qc!_$T_6cjz7YGe+ zsH+WJxp@xwaO-S+`?0sP-{r)s&QWobA~Ps@0j0pyB7eML5D;bi>^4cIj|#>WM@s&b zNaaV&ZUMUfQLgk#b5fy@QFF%wM`~{1J-)?C`WUkwY!#(^|I~EooINuNpUT zi#<0SQYu3|KfUARC=X@Y3((VcnXCl1JHa*iI8hucXR;2as2uf%i$s|^dfH_Cq=ue0 z;qBR#o2V=2X*(<-Q49|H>GGqaU49`Wf(@~Bcy&K}zsG!-gs_sLhi8_0?%l>mV4Z90 zW<2V*?Zcg8tXgfk)w&Lp?~a4HPixy3TQV4{KC*?r9JI<)8}eh#ed?PK!jMO(YE>UG zLxZlFp(9&=1G$o_R%j@h&C0R$7s(au^ z#g0rB?^?m+ZDB@7CcvjwP1v!b%`55_scCv#>E;~u6(Z?mxQ%Nf)66Ywx3|gyihh1=im8figIiso4+P$1ow>#B zh=kL-L&?ldzKs{@9Z_8Qoa_0?lETG$a_8F_r5fSXL8$`^gle+=6poA18!NHU6}bNG zN=+?-xP@eS=s`$oA<8F1LPvxcog^WtfkP9RrX12|kS=w(gjv0*ske~A8bp0N=9Krt`ZiZ|H}++Fj{m0>L6L1(>leQh6(tx1hWQQidT1HdCkz3Nf%M)Rwy5oB6xSJ zP5NEE1QjTZ4RtQ43gWS@zG;MhwPh66FseRZur3$*MAIO_^{H2y4$JSuO^h2Kz4}AO znvVneLq;_9iaA>X9S_Syi55K+1j54-^3W`KlQa*N^VXdsfZm%!n51lK|3B=#dwf*o zo%lb=Ou{4?G6Mt%$R$AV23BmqCQgt583;-+7)gi{&??!O^+Mqsl$OB6N!&~hQ`xQU z+E%+#b=R(T*WFr0Yat<+1Z0tmRS?jiQBNF-K`{vuGr#xeIWr+>``z#N_4@tUymIC| z=ed5K`}2IR^BF@U#gCEplnfDVZdOE%poOL8f6o~hLDRlDg2qNi5Q5EvM~~4O9%9aA z&WXxLITLv7jGD{8KsHRx#0T%OX=7xQH*<&-DY_>NtDf4(q%k|suriV;LlS-Qc_gy! zX+UDUj*ujg0~bgB6&YO2Frw}`4lJ%fLQ`T=OzCAJ9D_XQy?y5Q-$VqrG=h#W<3u@r z%ZzZ%IaxtLYO+q-mYR9QC@(|I30scBly4+Pr};RwDvx4SzUXw6V2%NZZ4c6bK$%u# zUP~vi48qA887aPkbQh8H%8d)8rSqjX#GkH@%o2y?7iD}AX$EKbz8E));!G*E_+7LS zF$S2~F$Ng)#rz-nU8X=H8v7f$aA>K#qWmr!A_%W-=np$X8@@&<=mueMaYf4*-!M#= zYz}D^^`ntLjTZE2I3dWVL-E#djJLRJ45CK)Yfh44CUSh2_3Tom4VSknt~EGXuH>tl zD=bIL!g$-j$ExP~XsBxI(h@U)?q?vDX}N)Z;dkqg*GE;wo2M7Zf`&ZAM>xE#ENJ6O z%%ix=SQ-mxQf5@LwID(h0gYB-<`T+XsyD%KC^o^s#}n%!Wg%C0OMX3zyQ|cEkrlrT zf{^r(#pX6cMqRb&Vk~!h$KMWSWL+f`Jy;EMEmlKCoSNAPqoFaRJAZ~FPAe!j|4HDG z;TiK|)0xho5H`QC+w@XQtBuLe(XGR}BC!Op*K~v@QBJY>xukD4M-0R>hv5ul2sfm8 zCD06F2-L=NEFKeC?=+ua6R)VLaP^$e0w<9u$OtT?A_gR40?_Y_HvdU`)-nINc>TJH z-yp3$6M7t$j;FE2Y`UzJgQmxPB8PHzyS%Nsn-sN;8{A0$3D@8dp`Hcah^!)w5CVgV zLXNlKC@~+Sax%mdgqqe2IwKEGF0yN-^U8$B*TQ)q4VfnmI{h;ig9xl~oD$fTrgGqs zbv&z^JB(N1vfQB>T14Tj495$s(kr_2kb^1VZqb6cd0AQ3p?Se&eX$6fOS+o^+SNJB zocgdLWqnsDb=rgoZ8|2W+Nq~?H^pmir~=Xr1VO~}9Tzq_Y54`=hh=?kSJ_2ozEEQR zP8HIuR&%*Z!Bl~iT?hQ0NMSyEnjQdd5wqfw6K7^hra})Cu}Wjs)_2bVj8%f|%^P@Ki_&K%yu z`K{5}Y$hp(3(=(rQZ|C>L2fOp+w1!B1=+SHEC}>pwf0Ql+=#WAfpeJ;Of-)Wtu@a% z6u`k??v+HYFJB}sn$=b|*PMHefVHD)&h6#>K&ts0E4mC3qW{wR0;$Ls2%Y6Jl<&Y6 z6WA&l%nXFv;$WA=@-M(4SU4JR~aoYG@F3tNo`~Y&8y# zeky}KmRijL7jqyjEZz&kKWA;bgSDqB+kBaA3Q+-t<#nV+QzTMee&v&Hh8IXuGp~R` zC`E9aN$Cv52g4qhB$PDzan9oNqKAMZ( z%G`KJoq3xBnJOlGV)#t4F@7-%ddUt+%X-CuXavXcIBjTYyl|?q@ae&jUc&0KV-;(bn7LJ2ipUUam_uuWXdB_k7?LAviXFQ0f~|)&8w5KZ!0wn+a__j#?uao~D5x)=Dt8>^mi#<$+MhSmhgA|Hc7{$7Zve?^Xix##d z=snudoi?&nQun9A-$5=;#WIgfXEke%FGD?wQkuEbPuY;2}=lKNl?S__ z<1ITPN_Go`?H8fCfOo- zM0wtXG>JTc#AC^SRFQdh4~@Pc|Ehi(sL1@7FNs*>O?Xnk8b`$Rob7VW(g8vcWs&to z=1vu@#C%!a9L`G26j5~5Wh}W1{Q*pSckMGI$vWiS3mR=McRBAaEk5Ej=FW^cX2cwM zF~{Oay_B;}(gzpZrQQ+iGpA^}mTcrrANZUppECzOXUOM_fzLeo%!_^+d5a@{bx+)@ zjmR0MyKBy=i{g-_rp_IY%HE}(2WAT<{=Ew&;-ilx1> zjaKkBmAD@n!Q^q*ip+PQH{Jb+oG!F=RqvqR0-u2Uz21Z@PzkXelSR$u$} z1Oy46ATDTbPBsHxi^+%J7bN)Ka0d&I$36wKh5LC4+Ah&7QTU{_yE9*DsH=qRAHq9BwM%z`KhDkiS*8&T!_G;fEp-}ec03}@4$G1@A!%G zQ$;5dff^JV?1X0#IzgDRtaG`QmDHuv&(ABL;`BDTAKAf&yH=H`B#Mn#%l|-D+{y<1)8fsUq|ls5_UNbX-Qcsj+QPqYeg1PcauLa3)C{-`NurWED1Ru8>6- z>8M8XG)D>F^Xd*om_f3(snsX!Hx$Z7sEAl1GJ>@F6~vQO6f0}7A)M7%3?{V$y&m|Y#FwqCmz3b+CgpN(kEbZ`*qOQ9xOkl5S3>Ykr1zClIFI+)a?+*ZGovu zG`ZXNi9=guu2%c1R#F8c?y0Qqq6L-vfHF8sqMF^i)Yi=!JA=)|fW{4{q`T={nsFfT zsk`Q+&?b7`z2s2Op(zKs9DnMT4{j{&dSY;vltTTp8cqM@oFzHZMz0P#BBTSW(!m%s ze+K^&W(Zjtj~Kqxr4>`VHdoB<+PoAUX8JPo1|`N*22%sO-lnmEUb{Yp*u_gFyeh@) zxJfnvPgsN4x;U0oxI&^FSLXJRbXH~(m=ltq${C((zKVR6@YGW3314s7yPd*3oBzX9 z@^Gp=ddteflVNVr|4exCH?#1VO{&y!Ql%Ic#{a|A1btYA@x%(+)Bk3?|C9dT%?Udy z{xD}mMevE0cpm+&{QkiOcJJs%!Jpp4$1hL(@pfJN>dMAy~%;sZ%{64ig_FMVwuDhGxJk4oUbx5=Ijys;< zpgEe4?)giRlcJHsL!z2VU!OSIEQi>d4{R)4fxVk65Xw(HdQWCz^KWc6_;nMv z522Ntk0-Py0sbnsGkKBoO`-QCUXa)eGHz30=LiKfxPdz57X?hOcfvH>h zV2yrMUQa#AFU-(GMUcNW;c0$>!j{*(O@c!%|29dAa65`o7(3I7Ts2>bh4HmXLO^O- z`zgh$Eremp5fK&Qx~tUapSHmjXz6SE%x%1R_Z~+)%$-}}@&PPZ*kzTZe)7J_nl zhk)YHxNA`7zU-_~(idFTYb-n4y(=zQ?$WiUuN*f7zM8Y%UNz@d<3@+*d!HBhD&r4; z=U+F**n2n}S{(1_IXr2__Wb@NeF^|f8WSEDx}kj_Y==QHH6<6k%0c;oQtp0_7yz`NM)&?gB{ z*M!H0ZfsZnFIvz_kb?IIfJrV+_(5Rrw{nEJL$r1yz>dCrXQ28lOr_p;-L-y7fJG_f zI%t#;+X<&sko2fxBK;DFcZpNKy@BScFLd`e(TerB*G=_Tqk$sT*sI#~a2R-!#wfRH z-TdwON$KG$R3s10Iw)3|gYQ?RR);?g)hf7?VAbdYTbe(EgK$^GX>m4glffobf8p9N zhCa)eF>5)4veK4kvo)P`+Y4NOu=yDWOCxVv;VMZq@1!E9`ZV%9R$$=idg)SI%(uT_ zzU3_N_&3bA=}9Ot>Q_F22O+uNjiz+8ctze;UMTUpFf&BEg&O3>NHxSA{-*YLqfJGe z))rbk?9|dwK^pQ3_TO?n5)JsS$WWOS-UO-BdPm@1XPTNFY7P|j@`FW`f+(;QSsI(Zw*v~8Vitu}%>io;su>&2K;o8E?w%{;8!Ji3;SbHM ziHwxljlSsx9>sJwzY3m%45Yqgf+AeKA{y$_hl4{NC`~FJJ`h;qjKEX3$q`AAN@4yY z;8eSXOW}TZ{m=T1X-#U>2DZt-uZeH1dSTH$pxAM`wyWT zaERKsz+Jz}hiJGk_}Z^z;500l-_X|IRNF{@)i0S3_WD7G8f(nWPkRncDsmdl3OTA4 zHI$voqDC|5SSf(T=$&bpxo;WW^r_p}`;CR|tZ`Ex3QZPy&xj^YV`32gDDcWZUItiT zRj|Z>!+zBJh5HdNE>@tXbB;xUb8}E?wmz|HP8n}wmBWkn{`rA((PeI|Ov>KS;yAU= zZIyNIQdu>|geL}?Sm!PTKE73|H)yHD;3#-T);x?QY<31WfXDGn+aFhmYK%Uc`^R#} zHz4^Ix|$-6n*xzJSTgOCwRV+Jel|4je6ZZZIw|SPJ;5@xj5%asxzWk5x6G-RHY^^( zVlsloB*J1c#IbIizj}l$CT|W}CdP#Fx8@sfhBH){Cv?*{){t5SG~Ti4j)HR9yf2jh z-9AijE{^MCnOo*U#4$LpFPQ(`-p*W_4*et9yxgIyr5(#%S0DtqBrbSkUuZ=Zd|RHT ze#eqP{~R_E{G>`NyJ7Wn*D(~iYxPBgRe&%n-X!}<|G>VopWQ=CjJ0>_g?(j-+E-M_ zw;G#$h4y|xt+@|~eF|B2b$Crs=NE&=DzNZu$aO|6)}prUN2+~qk7Bx3- z!RO$@F>X1>`FR?rqBF5kTiClvhOF>_2=)jI8{Qk7`U<9*npoAB8gI(HN8fKYgOrQ- zloj>)L7slMo&{=_W5J}9@N_1X6>W>!Fs;~=#`L>Mp{EdusFQAVM2``@l;bph=m>6b zP@wTcSufnRA(=1(0~Xt*M1V`_27aAUxK>&NHidP-8nD$<{M9KmoEnkF{==Uod5sHW zw=Zd9eZCwih%)rTxJ~+zoXA42S)eXySLda}r<1n;qxK*|2c7scy-yrN34+;zfK87%Jz^tZeJ;S4Q=s;cKd zAr`BBsrfowDp04}z0L00rwNQ|$XZ-dT4eqP&MHn35L1*klk5_6J&b@t%Z9piCCs=5 zqC2DoB}pwsrJ`c5^ED)+&9!7nj%4r?T(EHEly~Si0$yTPH_}4vN1{jzM@ez)Kq2P> zE88i5A=`hFY(@F)e3f6CB9z<&usP-J`eZV;lktUIO9!%*a|+oS0xyoX#z8TS$z>w!_xoH3adgHs)Rn)Q*Yh|VH z1E~`{0Dh`6pRO7ZGagkrlTR*5!p1{GCR%Dv)bGej{PtBj%?aRmg=f~hU6n4fr74Pr z6(2beXmOyT)4BGumCf7g5xgRgAyyt`C8e);X3Vqgyquq`M(>-(nRTN%v&@kJ1_Jz` zB<)%IXS}9YzWgA%$~M0kiR`cu+i2P8;sy7_I``m$de)wavFa4bfUAbI2w0m0ETMEl z-dvC~D-+2N(Yol2j9fzvsN6l$&a*P`Z}543Es`M!-s<1WnJv1;w29k9X&9JNr98}= zAf9WJu{6-CeFPiN$;z3)vVA%~W*loyS!JGlXUq2)`p2S+$rUoE+M`bjs`7<={7(dC zv8pe?UvmQIB&0Ino`?r()ChBO7A=o6L8L7<|0DsPu2 z_#vdfnEJTu7$9q<48`Fg>Mj2PN`%ZFdL_kJ-xoNYBs})QJ*mcMCO`|bG!$2;bOU!> zjpl-W(PAzqb6CPU$agik&B5xP+_n2iEb`fMOhV=$#gba?6p6Y(TU<;EJE_DB(Kcm> zq=^g)Ji~B=2nU8@LzT%3FNn5Qcp~n_P)7HzhxF^vhJ^5DsW#d;*Az)Ga{nlTKbEqt zQ0^n)gq85ZxOrjAjK+H z^NZ?OOhVrrnK=U%ESjCkkYh0iRVA$Swx9~_-`*E&c@nK^K7%tjBkT$E-s`Ttl#+_f zU*aWr%9(LqC=P|a_BIi% zhI1C?+7^ldL)Ku+9gCbVAGt%dlzRL8h|klxh0jGfg`Rb2a`xnjVzR`5&l4YJe0jq6 z5yPqw#$bGrB4fzlDnuv!kU zwy;>iGQ|n43e9vfV+!72ml|N2dhmZ?np$3LmQP~*4rZE)Y7Z|q_d_^mGO~n+N1Od8 z20E$_XCULRF;V?i@@qEtUx>di8XqRAkDyLA2Tm0f|H1Fz5^rw!k0=pcI{5^h{FF?F z)&$}B%AiL=^%5^Ufy<_-8WyWKEqMva#!xk98Z&E}Bpk%jd&^41%1Ro`VLbz_0x_=z z5R5v>1N2{kpcGDsJ3CZ~8vm=oJ$kl-#I$*PH=<-PXSNhry<|r%uVV8myJ8oNUZY9ItGJR6~%iDVWrbfG^!w|MwJdPd=*d;x%foKkIK07VE>LSj#!fVnF-`Ai~Kio<#A_51hBVx2$E@MrKK?Mn-O= z6d9#r(xxEBy7tTj7E<^Nb&vVfvDnZ8!j;WRC!X3q(gATx3`E)RgwI+=Jo6rvE!Ct` zY=h&C{V)|?Xgd^~p|>Kx#^KNSI;M%)FOvhS75{IOBM&J5^5mFB{RSq-$#-KlFyF`d z*C)qT$*}dDom0mTpC8GeVCtbfL5^-TPzla@UQNbfVu6HVt>}`y}=55>#>r=NCMLDq3@{k6(A~r~Fnr zh>s|G(arTgt>rs1@=;ou#ms|e<;G;rPv&QD(b8q1YQNE1WPbi%P)-89xn=7o%jbuD zih>(|!1Pwx?Y)%`lBCo;1-l4@uu`*`@W@Mx0nIpKzQji;-#)G^&}c71F``-b9I202 zt{_dZSx+$tO#dUV%H_)EVVqXtV)KXM?a7FEX+74%JBm6@^qOk!#H& zN`W8s+A8SEGQ=51TX}_^(a6mR)f3r7Q;3a)v*vYK`1dr&8cZ8X&996$mOiOc+DWPA z+jcqUDp?db6)HW6=FM_CQs^(FIn6IQ_J~^ME~Dg@ZFiw5!q}UWqYVv>%L_EQLgRkn zePiusVw}wJ5Q;b*1jVC#X^*>hIIVA#In_5gc94zS<`tb0K+}T>( z!Vwuv*EQ>(h8%xnZ(#JMJu4&Bd%i3uPiY$NNAWo z|Mj!Wv@y%fj(@|BXEWl(+V_yR5@9VwxLO_dFS94;ha#$E^VxspurgkN2u^HG@B1T6gIQji%?k;Ew_c5wO2%l6zf-MjgW`lrR)8JfNMc@R zC3D!y+D6vYx^t4uY9$V9XXTC9S6K)vWosoXk~3RI4&x>sL3g#-?U+H2l$5q4%v>}t zw%%(XQdIQ4WUVlBRb?75s)hl>AhKdP(9{l#)A>$*riUzMdqu|$jD+FKsSdP zRZ}H?$aTFWAwjYvz@S#yQ=-L_@h2)hqX)L7OSffHelZ6ZWA^h5b(*l-+guf2u3r^- z$LPXHt*bRbqR1EtPq22sK<|U_8omCM_@i7vUc!x6%|viUQ*EfonP9YNsrJ_^FkpPn zdVOxpewH$di;JhV6d&wG?XT79pChM?OuCMsv8x`?}@?Cm~G4`H_)Nim!m*l|4aA&dW~M&&yBu zw3a->TxLE@IchdSgouPwsJ=Pld9|04~ji5RP^@-bF=Q*UH<^>sWydY-MO zTD{gyRtHva3oOZ6$~UA@0=^DM_)q2rl1U!VN*>o(dAw-lA+P_dJZ4EAv3V=vmPn`C zO5L@>bA=&rW=r7wX7|G^qCzyNIWK*+Zeq@+%h9fd2IqQ2kr*9ZN*0J&faOzK0rv++ zNr4>8napk7`8UM*Ej~kMeR)!gFBv|=r22Aai!X_WD2=R##jvl+E=-2bB1=SceVSSR zU5ekGL1svN>51-_P^LZ3{ZirAXh~b$m(s*p@BG}2&cOLwL-R8>#Ybrr=2Ce026J7W zK~9X0MYn~B&d}nVIGt4)Wk2sZS2eM0+TOt4$l(u!2;6h1F0BR~+l|eE+!~wS!}f3A zc$WQ1rNDNGN`u4(U<6CWUT_gWR@AmIDsM zdMY?7rzu=4B9+c0bppPmsIr$$N_%X+_h@xeDEF~xZ)7!o@f?#yT^-Wgw?UMS&=+_9Hi|X#GjFmq(_V=7)GsPN+=qTKK_!F?) zS&dgLbM?FVLAh}m2+3|7 zVhjtW1;UO%X24bu=tN&awW+{W_xE(F=6<;#IZ9?ahYmYG=mAJi1&LBjLA?8ATT{EI z<`Yq@T=Q9E4!@B&Ml#@VDd#F&q)*5?W{$O*&RzFMhHt3)>~qgO2OvrXl5qW+@3VS= z&X9Y&c?WKebM#)^LNqu4?GmT=Ty=6*qm?k6>+Ri~JFQhtg2FIN6464014QKBK^djv zM#Lr0it~cXHUpAjo%j04de_EDu?+o%J${uYmLKW`Ezj zpHQSy8fC;SaT)79hd*R9?KyhM9-75w^QRn5DL)(N&(ntrL3~*+6sq8`a5C6u9W6qx z;271el^RDQK~KqJ{!9VoYOdTe*jFh`0+XfsAngJN97eZ5a|p8wm1eo5rz3&7rD^dY^fTjQO1r_X6anN%QX5-tqA5=S)9 z;s(ZLM>e&mq_m}o3QlL!2Pt*?g-+{1?YA<5ee~c5P2q_thwXc6xHEAZej7?}(5ao2 z`SoT6q}&VB#ZuVG&<8=l8mju`3YwPt3`#jcLJq^!M@a87`kr~F;u%xy*g%RisznIj zy~Fo*Fwwo!_ZFx%G4fezc2FSX0aoAOCKpIV7BLQ~;9s1T+hwC^dxe%`4HJZ?Ii65h z_XcxPR@o8qWS84#Szm+8rc-!!L|#CQox(X_zdkgjHJp_4dYH6~+bQp8Dc(QnE;5Sa$ige$*4>IoQMt<8VN(!! zw79$raKzw(Q!UWuQSgF)?P*qgX9A+}#;XFul)WW86c|%1o_=kVcR!`=)kh2!P{R}o zP*Nx`8gIywU`OJR$iSi}rnH3PQ+7$V4%eg{006-;g)G3@eKJM3s!ISh6I*%ml?~p zM0{HshR^kXm5lJFueQZDG%w=YDyxTYYfbf5X}ygHWodtGTCdkvF~|H|osMK-fy)KUV~bqQ*1732(8I&{aD?Wj5r7wy*#-+w;0|O=71O1| ztB{{-?HqYxgn_7PSg>pE9iZ0&?Rhd?SaeIcy6jgiyO>#$vnEYgkA0qs*%8|V)9b}J zWH>9d%yn}~WXShRcb|)$=ZD1m6YgV;n|p66LH!-~(yJb~mHucfX?!y3_ri2wv&!%CM0VT@*U! z>KJ`%;Q$TQC~xAy06$={~j*T@rt^2gLGJR2Up?Y5NE4ExxEr4 z7)SK$N@A>E7Soq#Gtj5z%vKcG@d$VSij0H;yPoC?r$T?FoI4mtTmf3mJfIap%Ps-E z_rFEZ5&|~c*;$Ff23=)e6|8Re&KB)=)g?v`x8Xs8kMoqcBr?B!TZt}+Z_KlF1R`l0 zFOS8tWE~gN@ybU8B1?ZtWc7tWpQckS(@tf}rL92TQuKDvEp_h}_YVMj$x zPT{TYI;E9qZmzwlCR>b~SPTReH4mnzkU+|xcC;e!V4{sHKpLE0>F$Sz;%Urvd5^4h z8%v$`1KxMnC3erf%&$LC6<1jgJdu$vSf$rRWIr1!fTK_5;HD8+G|uNECtGuhFbz5} z&w@g_s>*$v_l?c*#?h=pb;mXi4>^7+)iP$x^BxXn8~vM32hMq_hs+JCoT_Yt3h8`; z62Jp&MzQ>l|4~XCFJ;F7IV^+jhj>R@O8bs##n75aUH3*$%+tPP!&$C`Py#*GiFr>6 zxWov@YiJlE9`J+|Jf6AU{lN3prqeMP4tI(&4^|F!{u4v!$R*3~g2>42stv%qc8j^v zi^J~vR+tmYc4Xvh7x`cHG<$(IS)`6e2h5?!@F=Zw+eIRxdHZnn>)^oAynUFsORMs@ zvh2(QTld9t|DM(ORQ_U&yIjuaQyKj1EaH)|G$BFg;j}??5L1Y^Ku*ENdHmUq;;e5D7dgrbk6X?D5fwWjAZT_Z=XciL# zy?3k~5$OHl1F5lm+Wegv;r2nf?BGDZ()|0gkx2B07L%7{h2ggH1w8`J=N4&sBF)RH^T?s;aJod9zmDSy$FF>3^Bpkk_8nB^!Dq+TNC6hp+Rzj(&Dyl|%#Al0e%G^puNzh%aFKJ&sK!-Ydccw5kikv8SOAYy%3T2AAJbd(J1rCWpZ_`vYYdc%k7i{ zq<5&0b4yCsEfcxB0ZlBTz*daD38zRPH!-4L8>OBVbG}N`Cj>eXYF?x{7wIF4tImd< z#Z_O1?Zs8yk&*l83}Xn}J=$4OviJBO2adqMz!~5OEbF+ELK!G~`ClztU4Y`W@4-EZ z9Sn=wsZY#moYodAzDSBMlH!Xl6d!OU%D5Y4j=xa+B^MRX?b$jCubc4gb1>EsxOZ`% zHn6ey?rQ@zID*rvfnWwaGJ^l(H|&N`2;US!b*r?RqcL`%o>>ElYo$}4O9%XTr;I3c z8t{F&BKbpgFEY=wKPbHh!=h>o9<3uDsITyJVFM85lUK;VZ56%0pJ4hAy{<}EPAI<~ zt!GO0FJ~X~`+$MM2qz`oze7d@hg|S^a^W1X{QzW;&m~nReI#=*Luzp9S($?!5#$^f zNmAjesG&^0kIJ`VQbV^)Ad=?}UCvN7W-8_;&H}Z&h{xI2a44SyKN}<_Py+vgclQER zMO0V~PykpV$t$WyMH*rHg+}NmnQDZQ(MEWrmbi*VXg4|05Hy@Q6=!Iri&Iwy;7j(} z1U{rLftJipon_0YK91rU3j2Hdnpu&GFvBzpwx3sJmVwcIv*~1lm^kcUwT$TH3p=Nf zY=^*IV(v0X#H8m6njdnh8U^E`%p%4x``g}K>qZN&3hW}nt|F`}Fp7{Me6r~i;pQwg zKmM95psY9s?s>7pZqvWXd`&SAGK3TnBwMY2_zqk=-GLBQ{9kx`?kzTJq>#b9J=dTR zN&M*91GEO^4_wPTz&DE&Fh*XrF=qO!6j#_0beajc{)*P5F#uF-z9tzqnQSTJ`7d_z=OtmvmY@z~kyUhgNVP%ZtS{kO7pZ9EnP`YU)Ac9jki%Gq{WdZ64K)Eb1>ENU_)mKI5$H> z{Y;)V)|{t669qD69?swl7M9K)iiL+NJQA+8c!IOU(xD2t1`I(2MKK9xyXTqb7v!UV$;4e+m^^{ z0_qQ@n7`jH?WBPD9Zn0FyUCoCL{`GyX9W)Q1Jt$d@Z-{k8$;Wn9QGWXQkagRPGPux zHcuPvFZ?_XYl)z*Snmjrm(kSg=-%zo;!}E_&A>Q}guU{rM;7Y)p}P^koJ|_&KE_gq|GWB|`fjguiFFvEm!27Oj{SQMEMAY=n0X8SE5x zm3m*qzdBM-pP%Z`r=uI|@@`*Ryfzs_G_X7W7A7DN09-SJzApU=a}@>FWCs9QzYT6W zj9L@h302!35{snH3?VNHzZ{Hw{Y9ms*~9$kZIuVJVU)kRf2?rVc9oikCUZ`OL#Yge z8;4(%!44FqKZBkb?xba%bNbmW(<%#OivG`2WFu1u^sl9;QqciK`>%1!%u#b$gta zIY@IMYtqQdTZqaW7q;i8qLGugulZ^8%K}hLLq#y+(jG>8D4Ld)u4M`nng5#V4yffw zV1Y+ankPBS$__JCKvhJH6$+y%;{OPVK(6zI^aDYCU(okLt51|eaG+{K2Q)Tfuvrr` zUb7vu7!7Wr|MQci!3mHotO`SQ`@--i7*7fGrnvuM9TN!~IPPD}#Wc+|8(seMIh%)6 z**nMLf1R=_rw^%0=$yx=Tg>20(v3V_zW43AX#xd!sH!c=Y#MRPkrMcuUmA(cfHG>*;@{79r$-?IXiSz^U?*FMiz zm80|LylA`7P5r^b#%LX7qFKG*uKf?(Vp`-Eyp?GYk;1QXc0R@{YIY@Tj{?~%U8{N^ z|0X&tQ2m;<#JFpVC>xvCIli{_9)I;G2^;PGzE76WAPgv}vio5Xk?VY&OeGI&wd8D0 zs!CdZQ|BMph@=6w7}bs8e-Bh=*tiy{5fZv70?3-Dpg_MgQ21h`YRK}=5V7T5C-3Ct zH(_4ST_-BjJB5Y}Ovbs+)s`y?d{%dOq%vFdQb?P7pr*eljU8b`te-At;gNni5l+~# zl#rnQJdGJn#H<^4vm((!-(D%@*OBLM>6#c-}7jx z!}4+Ai`DTM<@W8)DSTSD+kNRdh0p5XsmIM$#eZk^3*ks)BfOqzEHkHy%tt1Xco||n zrw#pc!`Dq7;j6L6qBbR{zT1Ter>J*XY{=W0L~v)}kRF%YEk*>6K|xLNy|60ygT!E2 zd_{0>GG;z1g2UvNe4Cm7kzC94pUt(k@m%rGn7-tBgy$2UA&25+J!AbXlEQsNe(FN1|&1BlI zTNX)!th)8lrBK}ZI$6rOFV=Nyf7j}3mqJUUu)qQlE1eY^Gkj^H6`Ivn+CX*)1Q*cv zZO-wN1=e@g_> zd-;rdW1&F3J?2lNCS!uilyFed>L=S)tz3&6Vms!z@wnndTDp z9%n94?`-pW_0Bb~#pVe0E;3Wp`xeu#-pkGNn<7BG z!u&$LZ#Tp0eV6&6dRLmq)cYRuuzIgC-%xMOY*z0F%|EF3M)P;P1%#LUbfo!=_`Xyt z&R-~};wybbIk$*!t#WP^=LY2zE>-hB<&-tiyi++J7w2;2d{Uf+%K5Z7=PBp2;`|;? zxLrY9ib65E>J}r>82WrJTx)R}%9l6d5+%)U;-Tou5e=K`kU)Pl@bhX3T<_eb(yeh4 zHmg>Jm6&f!*g*E~+P#!2+Dol6=DH-G`e;7?uJT!ckiE)iu15m5L<2)sU|K9NO#-(@ z1J_uA>9N3c34AmfSZoE3iv^C8z{jG2*II!Yu|UocsE>;Vj!}W@GouyDBy84`Dy+o( zdZVh?McPjG?c)$rlGP~88}cVo!`KXtM}J-tI`-VpIWog%!2SjHMDR!5UPGb^YKe0{ z<;Yxj8nZpSGobok$P^5Tt5g_z;d8Z>6hi~TvU^VpmjfGoQ64=7B&@rxj?eIA4T*u4 zxEM8Gn^ubf0xPEekwVt$cLYAPqh)v?8Zo{X2*>Gv7J}4mD_1r5v`WU>s8}ZMS{YE5 zul}i(iDm_otoyc=B!m+{=?;d2K>HUf$%8A7c2wa$3Z4eM}hE!r~+Y^r9fEU z9UL7_ulYc@EpVmcqCi|IA62<>KqOy5bit+Iz^!*v33uHCOp+MX7g`Jbh>+-5_-+t2 zA+URWE{&A(4vY+1_HSgJ)P^;rUgy@A(^A6qV8&_V8&VraXCKsk4NKx0O5<>O1Fi7^ zjBA_m`iFuj0*RscAf|osZ`x(Xl0Kufk651UFLhT_r>E&t4`1=wUv4LR+a-;w0!NTG z0EXShD8rq-7qyC%GA{eH{+>8S2)97QhWZn2$sfM(yqJqNQ2oK^9Glb&k| zoXYdyN#(aHaMC&8)v3G!Cmk`LrcS%^n)2oap9IV24SdXNxj)x7YeT3NlxEMfj+oPl z=H#faLoTL7NZR1yx|*me>oO8wQH&-{+RWK<`_?ATR=g!HbYfum#Tjtg!x_9G-JL{k zJk0S#xxY?%1LJU#Ng$(7GGUHPY0@&Ro4TZ)tinDNRktd|CxJZgUNAKrKWUWVWc>-8 z93t4*QH!)8i}Z1mMxl2$b;@3najc>hEjNu8Og)iTbYdd+#z ztoXL!%Iaot#~WXqNXR%iS1G1GF(j(m&20#6=fn^(!J;(BnT0evB7at0YMN}|064kV zoZC;oRwo}HDp^47DZXF|J>iEA<1mc(oY@;V=C>o><*5kzy0_cGGI-mnCr)dsE$`A2 zIg0|s!F#)E%g+in?F;|Gd(Rf=AHpf-q}^h5Juxv%w7Tw9$ntv3-vf>y4!?%oz1zn? z9Y(z}v=nRx{z3(P{25YM-7C>UWidb@jKY$+X&fA_n@5`mpAj4vCt{G|uPgT?abv;R z!8CVNC4@(@1}Lpoj2K5%d^qvhINoTu;;s~Ek3ZOMVHq;u!gamg#!l`nbZK|x1$xJC zJT3BH;APR8gj}c31Wy(Of8k390fbsKVG9Uiv&5GHAFkoc0Hd8)BK1AVw;C_WbV&Bv=19xTS^^1SV=OGOK(+px1DH%xf*WlH}@(xMr z`^5=@&;oWE``u+^e8QLh4S+ogUe7%#Eh^ z9d`DQ%9|O$?Bz%MNPohSDV%Sjke$9kpP^BhiekEie#Q*egKAE?xy__BF--euY}JZc zhiXI=t825KEL!A8bDt`2w!9*Gl6cARxRQ*v_ikoAZ>#XO;bjkxuBbUjsu4XtR|Jk! z%)~EqVn^Juyqvu?Y9Ps)dcYA=shD*1bk?Cxwo+Tx9&FmClEL>?1}H{J$SHJcw-EVN znL&dmS^_}HO)os`;A&U5FU7BcXLZFLT$lf42gO~pDL~f>gCym*>6xXp2EVs0) zVoVglX6KYbVM_GD?QgLn!ll|r(xnX?M1`WBa_p)jtYybmWV(Kdz^UdzBc0_%NBxoy z&KFwpv8y_WBtCL%pn1^!cjm+qzSxeBh9$u2(SQt1x$Ib+&(^pEYWK^c_KCwpVnJz; zqP1xST4sSZzCasQpsZ34DbTelPk2;oBBRF^uB;j!POcgjPONf-%HHkIJp` zeku)5F%P3q^-rbqg@!(DAWep(8Cto*@_1?-pWEbz8Jin9!0&iOL6)KxwXh5RIk3Bu z0Pnj037C5TR_(!e3wapo?ToF;h{t!Ym_JoDbCUkWaWe+O_Xn7Y{ZN84Mibo zn=av0#c)}aovu0ayl-$j*du&8)0*OZY1<^C!sr}ljEF82IZG&vPCpJIE4~#hZwr?1 z%PG$oK*_4QW+}x)sf*`4O4WFbcuu`@9c1yeAM~g55m{J!25FI_upyj&5ms+ic_G?ks z!*1PZKF7|d&~iQRUDDn2o~SO_o>RVC!*szyu+U}Uu~r&uU=7aJ=*lTSBJF#`94|2u zd0+j!`EU?~ow`wr?U|74yGV-fUF-1fUk4X&9s!a$cjEsKmcQJ>IpiTpW$d?iml_W`nmQ*2XM|?X zNjU>wrtwbGrxOpJOxe3CxW<8$h85dDi(Y{s0nQnpAM9-Ucw&l3dvIg=rxqt1*d- zI?PU}zCZ10I_XI{gER&@3fDP;cI}qo|agZ%+uUehcP}&U*l+@@y>dQ7bSpeA4~$E~D%2 zMo%Gd1Xg$1;K1liZ#sn~Koth-gu$`p7fSNTg@X_c&Ur=zmgH z14?nkcR;l3#I^X&+w_+V-+_V#XMz9Rtk8{)jn{{hkl@mtBFg1$TK5HyBd;Q2@3&pq zJl$SD-;RRpmi%-KF8kh!a?}Nx>3f>}*)#M6Nz%=87~}F4fhmwAWl+#daV_%`Yho1y|M!P z&Sv?#vbut^9>?I14k1V0k{y?=%5)hF+tWB|2q#Z;@ONyxoC87D9*)%L#l&u|T22qZ z=fg**lO)k)I((Y(z)5rGqvX(9cZ6Bn&M@5Z7Tpp~+u4ZQ^34$6SMaSbY_}9%)Ey^s z(b55J7bBFai;(4Q_WvVmYFX$BiDW>8?U!vb(3pbSi}h2*)H0UD2{+*&D{eo3U(UFj^`xW``6crb^e~r5`4FF5bf5wT}@K#;~ z1bIb%FO@1Wt0mHa@{1Dl`(H{ax$x)x`bFW-8>&=J>?+M!g8`RN?jpF?L%FYdTi2cr zxfX?74c?|z>k=do?J3Pw8I^6)Vdms|kP~trYk>75lK#XIc7Ms+(7ijIR04Ra#1{uyAJ<&^Ob z#5wLOgTaAN8iNI7y@lJT+H_Yr|V-My(hiJh86|#)| zMqRnLyEqY=DHYNAR$NjQhg~2lBcPN+^oKc!Wz^dotn2*@mVnyxv}0Ag#4xXyU6r$50nI{_OO58-OHani$D8#6+3k!%mBRXto#y+AOlvPPKyBIg#~ z3l&EXN5qj%S*p6M^VJfxB#bp@4&-Kj7pK7*Hj|bO4k4G{ONAwa5;CHmM$0PDV$Bxi z`-YZ*ZTfPxQi&WcZ3fYNPla(~vel~{93sF!(M=V`f@BUgugd;CWp7sRlwHV*&?HDj zZ4RZyA%5Zx2;Ch-Mr5-)@LT2l>g%2EfB3cK+&Sj~(W!7P%dzW2En|ei#LmAbM{s3GO@k|I^|?U2 zvND@?Skzs%O^fU;oKqQ?A=J!@C1PY9+p!DmemMzQa`%5Wq5U(^)VH)Ka*g?fT6yHO z$lyLzfp!s0sRZtAkB<}{(c1#PQ}Gd>87Xv0#+x6n@j2rgWh>>7uxVi+3o9s(H0hVmBB7DxUo$CR54D0dFhH{ z-|w>dA8?~jd};*D{cM|`6U?kY_2&_NdSLbE@HTcw^znh!-84Bzgb2)!K4(R%?<<=> zoLUj_eHC^_eBHu*1LuTOx@p}d6-MFb6~R>Wng*A|gP{#BNla<22rfttUsBQY{v{DH z%1F0zWU6Vk`6HV#i5A=h-b=Btr|%vZF&=Bg{Nc&#WoHY7Z_h#c+}Ed-SEuxpqtiT( z8?bnKAnH?g&`G$K$D!EgYN~dzfeZ;W-@=A?sVEVe8K|ha-sWHHQU}~;B88uG%24xj zC8rRWf?20r`fiM?7WUm{{!{Y+6fOltRU##e0DYx{Ny~6=p$Q@*O=bZI7^TQ0S;^ji zwL+Gb!anmRl|@x{7|}8U)d%AAvBKvfQ&zk)82LJ9mExvWcIJCE=!_s|!K73JANc`9m2E`mTV`vGF)RHthh z2@;5jF%#=Oae3oOgndMW|SnPw9^?JdC6Q?TFgCp#BN)QM@<$v^RK7i@`ZaAxv1ykGhHoENLwI@3h9=}J?)*`V zgKx3uuW&3k<8NmXJS&1~M?{Fl5>(S3V7m+XUStLJ$O>AxeVd@ILK`AI?@Z~RcFyQp zB5P{k<1>MlVebDtWB|*Zte8+xw&J z|JcTH5zf$%+tseQwAdWR5!G0J7qXe(164P~{4d!)js$*`2A64c1FB=4M&f^#>;vvX7YZA6pxjiG+e=b4f1JaZZ z&XB9oh;KR>?|v!Y=|JAyZ?jG1vE^{ZNAuo}BItjA#9E|9VnNjutJg`Si>S|Pv#`^$5Gck4?T!WVIAa!11u?K0YM zibapl?pvFfef)v=_>Z%DaUH?clD!-K*UPQlc;1QvNpcwsL`aFa9?Dqjb4n= z&$nl!V~WeWl*6m~!x}|rUP&afJzxB%4EV?5hYDZl++NZj*?wHY?cWX$`9b1#{=TC> z5(*s<=h(Z5J$($Z|5QXj33J@jOX!{E?M33*h-WNw-rHXg&*ug_L!o-k8l7LFeq{Sw z60~(7NTmve?xKF3e8NFqClxn_9gfq8}JVmKHj-JMc{g@ z^U03^y0EdcKz$$R%v0~zI@|EyzERRWHIPnKR^X+)Y$@+a2@iZLe0%0N{QrKyKNQ-| zR@C`XGDU{k#QCmrJ}J&Oac*BD39gGJ;4o5TIto?)JSrg>u@DP_P~nT64;J>*k6;vz zFIMpyC0;Lm8int%TY#@aJU_HNW5BEMj?U#$?DX-3H-9UfLqm~SYvo%cQJ%awN+?ty z{WVfmB3qov%DG&ektC_*8gZVz;M}tqaGsXDZn-!w0Za9tL}-%;S>K8fDm>olbOG-v z2_Nwn!s-8F(my(Z@Goe%L6yb1J$)kn#|Hdmer?Yuzg+Qe9`KK)vg&`MYS-H(%9BJ1 z6&~rFFNM^K&yNQus(f-cI<228lLV5-wzED(R7ff^x0K5I=4egm#Y_HL6Z!^R5>5UF z7-^yaY_p+DkHwJmi(}~>c*$RDf^)zn(d6%2>CJ)iU9t4121@N3a7i?k{*@Wz)cKnQ zasvI^-``r`Z!Pe*7Wi8W{H+E4)&hTPfxorD-&){rEpSl_89X=e+|ILx$Ir8s=NCNx%Jbhm zyLjH_>EN+VjkgWwxt!-Zp2a*Xc<$lZ$n!Ivf8}|N=WU*kd3t&N`d?b!cL<#Notz4Z zbJaES>)$EAyyq-hvcLv9fAdx1u>5RENx4`5-Rk@AU9GL%aQ)C^TZa0}z534k?_0n6 z!BzLJURNpJ#FLoX+Pm+#@9*wey-xXAaia;=C@0*D~&}s93jJn>~5POv;p>?)x+~nI)Y}Qu)oj;LUgLH;cIdVYF`++;R6ktMAIt z?$5Y?&FcFyD)`E{?Eh=;OTgnQu5?SX0bw@dVaEyA8<=28Ey=svQnxlspbfXYKmu}0 zeWh;P>TY_mB*y{Skc?--juV`T12$nBAi>E4!X$oJm?b7*aRxH*IV?_M67oFBb3*dP z3Gn>>zv|Y#w_Dw|lganJ`Ce4*<5SD2Q>RWXx9U{gs~M?_jNW+C7)VCarlER38CwE> z{;0gJy`{xp?^mL*jPg{E88huLVj{6rIvDFQyAt7{RHP@>B`J(d661PWfYhGS4wa+_ zpp@OtwiYI_<;K%)xXr=+cWU$C)Cs%eO~{kx0hb z42!2yMJuz$kk`#pC|OXFEle`f7YTKB$3sI#I+*O^gp4`2v<eADy5^M)uq!d8Fb|JW!hPNDJ~|Q^yBc zbyX!FA9)g7{mUgKp4pjbFj*h$PefvU)##5oF{*SYhw?$wF*7S$b_8=dd7ODUU+>d& z?%pS#cU)EEdEnXf{lQeKy24v7akiY^&=8(-k)G;wGDD?Wp==#MQQ=@hPA!@zvC~uS ziC0c7u6b6jEwb{sMx#6aX#If2rB+8`D+O$_`&fQ*a9q7TQmrmAzO(5*)vgcWQIVCld!z&q2W3^R{*$zKWc~%4p)^ZW! zITVbgq9i3D=$wcwU3l$g<0Hex!)dv{MrtjKqh;~3dnMuMUp_C~Ns_arsqz@Q0V7nHx;y&#IJU9jC2MO9W<8bF zT7O1LFUH&2>l>`TNh#ezx_hRz4zd(xbyq7=$!_b&&0>^(tQj<-_faTPKcjP#s1HZ6 zW^b?A<6eJay(6PkBWc|shqa#Rs%vj;ZEsV_mZxlL@tg#l`M=DoN&;}kNM=m#)W!`dA;YbXt2|UZC_<3j`iKSnZcqIL1 zu^KHuX0e3X!}U)7_F*}yLY}g@RTWk9s*KT|tV-u8!(D{Pla3W$Z*L~0l$Xu1#1qUOk>MOdIb$H8l2pxlIu}Ip0@y<*xo?4;Hl3{CKMynkR4%q#7XVTW>K~tVG zRdj`d>0otFI2cKG^~KX+EC|w(Xxa>65J`KRB9LXBh~AbM!onz=h9Vrl>Y?OGa~1k* zsv5Q{EEM9g6l?+ujcc%T>4{=I_=0_ABv=MA=C^3A4$l0+OgbD-Vu#X|j>n_b9o)Ja zOXEGO&Galog_cLm0W&$vfMKC7X`&tL)uJD3>YUu8_*SaT=p2i8p(5R*o! z5l*KQ3(Ly~1_sJp@+od=_{pket585%-9&PI>a|Q72KaKPhvq1oT?R|$V1G20T0GTN z3MQXuFcd6{C;Q4PJ)Sw`6&2bb66guT@M(2%;jKYtH$$+)^C=#JiWX1Jq<3q(moTKkbcW`m<6}d~}YEWciXl(ie*- z&5mdgrXaPabH~UQRea3>$yaZuV>+xFUD71u@ic7~)fFdtTa0e;xUXGI|fwHK#pqU)PQxGYBWw&7J)Y3abA$I z{vM20J66yCq*pe-05`RH)3Z~^kIuCLMH^)AKi&H)Z#3Q$jKXedZ{@I=!}9MN8O@cFth`*|R@X)no(iMGjAAv4 ze#9u*78VV3LxYr~6cw-Z$&|)u&{_d%SxMn-TiNAr?5b}L_-k7lu)=ILEJS-Amm4M740M(^D`*wznnn?yMDTS_CQybBQvy9v)hZjEI$6W=0H1S>u9damdTyK+`4?`w3Wl^=k!1qT_}=l z@AbzbsdyTbBrHsv6KK!Oj@GrzD#K+isEcEH8#8GWsYd1NTD$x>=kqUV$TBLpsWeBI zEZTJ8Cd*-#k0e)bUS;%XvtT*xww?KlcG#o0@nvIFuT2D8}LgpZkZ!Ouf zo-5tKp4ELxSg%8!VJyNzt-;jl>WbM_6?5mznKyT~w>&R_6j$reo6eup6`f6=%TgK7 zq5J#^%xss1gE2E13r3Z+cFug!S^4x6o#RL^=(FvY=%azgu7)=GxM^M1(%IbEgtb<^ zYp~`|cbB6^JLm$k)lo+<|twoVkVS%~G+s&?&l5543W}Fq5!&CJ=_uA4OBZ=+uQ<45ooSJiLvNVVJ zy(_Q+6N8nKO|RR$CDI>J<}AA(L7)A>!M5&8)k!P*o;#Q=qo%D_dm6bil1pZpB|DZm zwY)lCKw58evSmf)FAq;ou64C+Rxm%Ud>}itRxq0ubBbJ^D|N^Qj7rV8CI&4#wNopb zvbwRQv#Yha&B(1 z%cjVYA2RX4t$MyJLV8JI^GA9o7^F}HW?4_gTU3DUxFd* z+q=ZcPb3g@ZF9p^far*Ixm{yeob5Lkz)ii?cVGU*;@KhpGa&}u{Oqpa<0p#HMl z^`JLApmr*)!NKZE&ulcTJ4O~_>nc3Z0keUmoHLh%I;dq)l;FvPKxD01jVE4}O)6vD zw2(bpG}&7qrW`%w28z*}aY?1Np)kLNRxj6fh|1Zsu_zwQ*bx;T>j_OxSsQ(HtiQmH z04bC`#kujJ>H#|f3>QMII@2d10ZiCB%O}>rbP!K^JF8)dh#OJZJ=g zz>D%m6YL{K00*;%Jf~e~%?=YQapo{g$>mml17%(41LwPA#{!$pUrCAAtyRFe-x(qZaK$D$n- z52-P$jk9>H2}UC!!?v0j=p-p{=?Tw5gY*V7(KOWwQ9Ug6<(FPsT$&Q1Ii~XAapAN} z!K_u4%v-v~$wv_&F?$j^n$?90mpw=3PdNFZRI7&_b9QKdcWr5p!$bBr1NF$@%&}0d zWy!d28gibIoTo}t(&{uIuRS2V&^5fktQWTcU_~r5jC!R*Ba%`IgcQuLUFjOG64;jaUh2~9Mn($f*lI+1BV??W)ywxzqxqdpx zMwSNLM9NeqRj~JzR(WPndTeY`aoKNG@5`x2&ymY<+6#rOHqC^QN<<@R_N_9MQJJrd zta^lS^8?d^ss;7b6dynb1tTy_sySqh868r5%Z%l0))duORXWeW;pgZIv?rt?e<8=| zvXq>{IXl-k1nmyiz_;qdDJS|=%sz&N`SQ!pSlEBZ z^k)3qCF8|#qYv?0zw(uTtEs~^WCK>|e#`)CP2) zEk}H^^!tl|z~^5X@B8W68;Q66@rCWx!21p#{@>rX@RCO!e)!?WcW;;Z#qb&*;^FFj z_z(HNV&&ho6JhY##PGh>?hZvS#*+^2Y9IddRaL!KlY~9L9DzOG@QIN}e1aFk*Tev6 z0Q}NjbI1og{PaD)ARm{0uJDOHK4AcSfQf*EZ<18H;U^C5r~HzBnRL&)^Y43i-A@)H zec#XKo>vpG=fFfcjT?cZg>7D2kmuHu{Nm}e{GuC=kYJSdYW8P*eFToRDL&mVdQ$!SiWsmQzKbi2@b;sY_m9PGhRldL3}<~MY%v;oeF#E6z0bnq#Nefecev;KXr0;d0)*5@BBn|dea5j;R8l?_}M8= zc*``u*bXo+!G%|+@R93^I!H8p`0x^ca|)*_>e6~6&h0Wd=E0%|t0E9w*08j#p{1&l zS&!$xB7v_ujXPc(Up#SqLqo%HbaOnSg9OIR`5h}yC=v5Ko)sOatYPpwd7@-hcom!w ziNqjW2`KP~^h!#AO7LS)%oH(^5mEg37b_8t;pw2fc02SeQuVqRxDr79Jq7%X6|eO< zZ?U3FdHrG+fbo-S{K5dxX}a&!t2D+v4}W7c)tEF*;((c!6EOWtTz)^hDd|_k0A)t; zzzRjNnpTc{-)r!TUjgVCp48|UX90AW_}!-L@WxA3m}x8EXFmGB)|yTCL7NI2BKsGH z_S7#sK7XhQ?RTW#jbijKn|^(f^D8<==jO1X$oUl)9otXmH=viI;&J1TJN|@{6DOQ> z@+qgDHu3aH|8T~cXPte{x#yif`4gYKz?d?1+VmM0UNrOKPhB#rw5;4yQCT&6&fIzP z7c5-lU0hw`^VinZH#9D3YQFTcme#iRj?0$@I+rb9vGR&5KmD1juI^eD?C!zJu`e9C zW_7eb7EfH8Or{WpwZhqPhP zjR21TOE>(3-!)$g`0c9Ndrtw}e8mTcc3lv=zsSPtasGzcQ3yO?WuL=E9L&^0;DRC_ zA;KI?$Z-l>!Lc5V_sMV~K0rS~#v`5NvK}8S^NT+M{5apoh>!I6TkB<_{olcw>x<{? z3QxIr?`bbq``9<}Y=qo&6BQDhN0eu?PhqVK6=Dwht_=G{T|C(^7)e_b4rEXD;8@v| z!${Mec};e|e={dMJ(ivBzt%63xOxqb0y=kMYt)bIcs^pr`5ykRTZhX_oCn;S8T$D0WnM5LZQfaWJ9A=;~MyaybgkxLX_gsgU}~phSzNpL<1h zV1a#Y&+1(I!g{eX@x~5BIAy}94nzw;(v){^APoD7)iJpG$C|4@5~E!Nb;cekh+Y=U z@C_MbAUIU^x9mF}sl&W|!i=HS;@CCB(x?OUYdON)0;U_8NfBB^lFRXIuzu6*G*k8B~GGzBb#m&{up($UXz%0csUj8uV_GBX!OTI0lXn65Btdoj`F>YJO=VltqqX<>i=!W1mMLWJOE8Le;zJwtG!wY5AHDu)NI1D}`o1L|SBqRo zza1teMh9S3(2@R3UnYeO@}-%mGlbjwD$og|A$_g! zn2ZSEB%bu(!Mw~TKrcW?8i91tg(Xlr*o$R|5M9_Lz&s_oh7dng0q}_4q}nm`VxvJB zy23+=IO^Wj6YQpfqqtha9YwDS3T{(+;wgcZvPfNMf$fI(|i+Eo7Z127X-J;o99kT}@ttFUBP3wQ;Nkcz?#dgJ*yGb^T!&EUX zAmiQZ6u;4(>FuQr9D4-r9k>eYHt`yE2)DxJvUC8~y4Cp*wn51Z`j=WATC1CjQWNy0 z7QA(j6=Ioz%?XYiti_MDFG&S^X*tGP81`r!2AG4eCv(q$rDVwHM@O9i!x)NomYSim z38FSzIxW-`wg;UbpL)RA7T#7=D`9SNtd$lP^w8dsDm0-$g|NUyN5kcvqgMzl3RVb< z%h45r%-RNMOWunEOm0bBwPSnU^0;5z0ia`8;wPQ(f9&v!y#S043=@nN3>u6b3?Ysr zIhHXzF-kF5F=jDzF@iCWF`hB3F}gX(E!U(ye+A|rMlfKLoQk|1o?4rOmYES@#1~m9 z?)Z(c*CqgNSB${coH*ux6mc7YnNH{CvxjMbTwdcq_kIp9@;HRJ`4#zjO@_U;5U<%t zb35{=N8C!_eDw<>EmtPWKb*sd`ESZYOP4nidp^j*%h}25ba83HTvkAK*j4h0hd;`G8LYJ`30k*baCfP_nB? z7=X(Gs{wZc9s=wJ901IFwn(f53<5R-wgYwp4gfv|vy}q;boBr~u7Y z@S%Ie;zu1!#&?5r9r=y8%4{k?!+fO8huu66czkw{x+UBMp1M7v@H1|Us~qw@=#t?j zSDI!}8&LK&2ipyz=9M4Ybc4lDg5 zmn(Cl;3G!>wk^{lmb0%jdg0;c?D0aHg)fH~jNX-s|a*fCmw zX9x0VosATrNw{eC=b>SFd{)!3zQml1R|zFo2|h=iZ@!(5c+%hI;$M%rT$f7|J_eeb z3eb=@`Q^jza%Uc=`iYL4?Fv)(ggq#O`X^BTjN6Ae>XZ84Zlxb|$-=TnT=kueuW08w z((H55tSmtD2N%t{W1!iZhlXWyeMHA{iTR9u1ZVTC*K^3DpOZHtj&2{~rW;IEuH-`a z_ptV(-Pkt*^M51o2gOU%(Pgm#Y;MI@irP@3c`u9M@)GJ6vK7)O?>vh#Q5VI_kE-TkE$lT>?4xsqognpv zd&77OYDkpGka`~(w`;~NS0__al9UcvHJd1DmzpX#tGGE;8w{=BH_|%NN%5F)A6&MN z>(r+<)U4F%LYF3V5x@DaW%sv=IajP zF_jv`xmto|55G8-9GKq0*B5BJ*)&cHD+|bwUiB1)`64X(%Bpb%l`DP?`;ciiIHy3k zK#a4TlwY)x*XRWCn*upjh<_Z1d%9*_IGF5=xAIi2b|`I%_WXQS2ysDiGpoQuH`(my z0DY$TtZtvnGbSx)7poSb64@Z)LKUvVn`$!r2Wjo8>%gC}VoB`{t@MAy*t!lXO?-+v zbLsd!-0#Sw!qkv5hG1;83e{T}=@;ihGJU+7+ta?yQk0h1M$qr-V!O7TajgRJL^d7j z8)Zxj-{v({V~VEY7Mzq>hhX5eu(+kJHJDJ`5nkjDgTr0LQYp9$DG!M8F+SOi&<%b} z-kp)2)mFb+#BiM&pH{EL03DGs4dFG3e!dmqPqDi6iE-3XLoC$Z%P1j+bSoe;tyV&O z&&eybs_zK7@4}3J5{$)+X<$qPV;UIKz?cTcG%%)tF%A6xpn-$`!!IV{&wgoV;;#C; zbN%9k<$kdn_X2)k-F;^I#(56i+pc(>_f4Vf5M?#~<@OzZpHH~saXgI=VaaQoKHNq` zD(s@Jd{HyjmkwtW==V2fygKfbx9)FY7T5b3B|c^Mfayd1qalR<5F|b+oF>?2DupowIqJrv~?Ki*x{Z1o!3gfhPG(ajj?pjI^nCBrb9@n5Zco zTnw+9#7R*;rW3~8m;G$ z+}v%2w*gbW`v5HOK>+E#17MwA0Wkdy0MpNbQm7xgB86;h1?{j-FBD%W{V%20d^Fbi z|2tr|H{G$wMw(o@b>3Q;U;p>!Ntk;Vsko+j3g_n0v~H~BaL4_>@c(y_L)X1yn_twN ztwS~*Ieb{Z4|BLi#U89F8ISkb0Al>f3Xs6@&pBw={W_}6#_@0rl}xCWbIDsL*2=ND z9hlk90VbdSEUA@aZU->ulFh*X02~G8+%+5cT;P*|&jWt_gj#Vv@D^as32ER@0Pi`z zRty5~0ES6bJPN!Pcnk1H!1b@=j1l-IgfSnEa9q!EAvg7O%E>j7@Z z@v-+5H7*!mR6JgaejoC$+Ay?XibeduyUMfeeudZHvyZ9~zUzi1ehBo>e0}fN4V66V z|MmYzMfoiJ#4*zQE&3-x|LVQ_?>$evcklc6e!4LK>$b@pm!qLB-+T35Lv-!EW^d(a z`q$okXWyT2NAWr(nVut_J00@{UH$807cd{-0Za!>2AlyP{mFpwfR85Dii3dn0dE2J0A2#@2J8Sl1lR&N zk?n5PjD2AcbKjQcqr>%<<6NopYXxn(Q2EXPdg?eeJ{|(*_<0nV<7YeY1;Cw?)Oc$F zW(}6z;YyflIP6jrB&jIGMauD?F$HTy90#8Id z$LmIfIi5=p=Cf7+vu_`Q&iKqe2+XPJec-9U`+=tc?*pC={1)&G;Maj!&E3Gt>38!E zacY9geV0!TC6W$LthaSOEIf!vsPMtxs&nFwK&Qp?uR|U6|F!(08vP8wT4)K}ejO*a z7W-`f?&BQ)pG$1NZ_CNHzvJ1{Z2$D%PtyM3FK<3e`;8q>pR4@icfNT3Ewkz0_Uo5k zIe*t{Z9e1R-A^PgdFUI@e=XwMbJfQ)-aGG>_Hz&1;JfzAZ+xll)Z=cx__4cvf7-dV z{@3d#-MW6mzxj50fBe9!hnp`L-1V9-{=&YSel`5!lJDO6kblSLS1-G0!Oee6>|0m6 z!J;`&ef!se)(79a zYVq?|E&Af!cU*b+ss|2kGe$b^ziD3ZM<0Lj$}he-ixe zHp@KsXDiSC&X0auv*)yFH!eAU$)nFd_?sHv15ZYxj~(|v=Y8QoP1WKZwQJw|@ur>s z@ynWBAAkHx@W#^zUV3DIO?k_wf7<%o)0@8Zix+F|crLIgQ~&ZAPyfqfHShF&chiD~ zZ+!AwuWqWDKJA5{?fCAZir^R5)&!Sb@yvDK3ap#-y{?)!ep7z)@lW6J`7=MPubEzR z|F0I@f6@QC{-ICReD2Y0`*(!aHST$PS#{56kAG=e=fDkzZ(qOo_CGH?cWuv%x{8rU zy;J__NAoue|WwKJ6!! zziGbh$^{Sn_s2Kf`q=TCK6m>5(s%B8<==OYfBS(q z@pt48ALhKV2yi8U&%(O^PXJyAd;q}pQsDu#0r~+t&qAbK0T=+_SuGw1yaxCkU?S+s t0j+>2V9bqaU`zvJ8W_{SmuVfU6hE6ZHfgPW+G^E0Hhsj}ta&wkT4{EZSZHibVpAj_yV*&y?d;C7J9(6* z(E3H`ha&z33Vst25d=X*3L<_e5kL7!tRQ|=@KtNu`1{>EvyUXZJ9(8>a+fo6XYQSQ z&OP^>-#Pd0x0CCCeDC9}H)L8lDwT3~szx5ldmliZq{=#x3RL)fcWP=%zZ5}rxjaA` zxC2>NxNBI2JJ)+9s2WrQS`AtSdKmNwXbosBh-*$-E)TW_y2ZxN5kuM~iF;bkV|D$P z%~F;1`FyOHb%e{4KW)7Hb)XWBmuN&Nr@+ycvvM5V2T^O6aoynax>+g$`77Y_GXZ?5 z(kl_k$T>M7aoinw6;~57dG9l22HXMu^dI^RcjzJ0QnFHxO~*1*S;~Yz8Uo` zpvORugSLVWfY|pb+_!0t>)HA2@TZmC& z{)INRHf)Z@2TUVmC!MryDVJLtN}ta-5zFW{Q+C=>?^c8(PK2yho#{GZ^b8D}3H7)p z9FJJ`kkKBCJ9e5K)^*v@xMdoBX4L4g(+Tx?O~KQukex``Ni(U(Uegy(#_X|7uKS9Y zdb>_=ut!2xJQcMg>6pX3oC(zeXjDaHjEL1mG>(IivUT7Wkf9e z`tjbz^C(bd92jHD0G<<)!ZicLbAUg+sN3ip#dRE5MD!a)+W>0iivj%cuz(g-{tKNq zUUNHArYNKx!jGK$fX5Da593L#TA2aKpL{o>pI`orQ=5wLC+eDz;hfS@T*bsva@2u8 z^I+nqU;d00FBjp@_(#pBpoKVABw0oayO4#GFR|J$e|oGJe>9JNSDLxs7HYp9N0k%c zLEEv;3Wl&25m>7s9ngiPETSK=lD5gLAp;tOo(#lLM(+{yw(!)0cOw#0`ZFX5UAM!^ z4aA8C{F>nvr!m5Q+&PY;{3eY$wQ%*G%Rqa#Fv~$DK?V|067PAbC7SMk)N~TM>w#`Z zlq{uD0QRT+k2dAk{cSRgVY8RL?);e(`Q^U>eS6*E=#@w{6|-BUemj4p(EMh*51xKNr09dQ#`gvr1G->%p3V@g$m7l z{np{(>UWO}SF>M@tM`_`1wc^~(&8q#Knnn>N$OEMCI3piFfwknCQ#2N3t_w(fTt&1%gVR; zQ)ts!Lh(q{;M)IO?C()1;&*p}OY!&iVqr|h0nJu|;7>f^{=~2UJ%PU53$PI9EX?1F zwmM%Lgy#<_{3B;Qd)oo6~K0cji{_{5Qr(tp5 z=9m92^zHEmnM<-q;R8-D%b!ynjo)SK(H zHa;>IbYZ0}wa&~OB3KFL52@_g1b2S0!F4fRHwfq$!)oO7Jqg|p_~f`U!!GPo z7#-NRTDY!@DcfPSTVBi&g9@m0zCYo{*Jdnl5ZO?%n?fmrT8y9y+ z6D=@V>^i^MYTd4>J^A+3n>Qz~z2C0FjDd#I&Zkd8IDo$rf)=QQjLM-+*y7w!2D`sBIhP1U43riQCzmYF<8o&JO(07|svf#Wgskla9aVE%< zM`vBRJgb-#+vgGg^5#T8)CoB$r+-D8J@ATOLM-Bi%{@~#zO11o% zt^MWJR?AIQtCYWSXGE%$f3m%9Wo!RtYqzttJ8o^YOu4na_`VaeBthI~TdsC=?lV(L zJ&)7q)dr~t5H)#9VrI{eC^bEc|0Bc-#?n6JoovVP4QI{M;ha{MHI|=w&aN>iY(_aV z$#^vX;{DIz{r}N}_)84t8630XatKKLC+>R1k0kri$vc1Y)4yCFk2mk-`YuKL|A7C@ zJ!*w?-!FSq0E+(uZ7(EgcPa<qvVdDw!LE>GROlK}tHjBs-X9?jY`;@*fF( BV4(m2 literal 0 HcmV?d00001 diff --git a/convex_decomposition/ConvexDecomposition/DecomposeSample.vcproj b/convex_decomposition/ConvexDecomposition/DecomposeSample.vcproj new file mode 100644 index 0000000..72ecf9b --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/DecomposeSample.vcproj @@ -0,0 +1,240 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/convex_decomposition/ConvexDecomposition/Makefile b/convex_decomposition/ConvexDecomposition/Makefile new file mode 100644 index 0000000..e92b84c --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/Makefile @@ -0,0 +1,93 @@ + + +OBJS = DecomposeSample.o \ + ConvexDecomposition/bestfit.o ConvexDecomposition/float_math.o \ + ConvexDecomposition/bestfitobb.o ConvexDecomposition/meshvolume.o \ + ConvexDecomposition/cd_hull.o ConvexDecomposition/planetri.o \ + ConvexDecomposition/cd_wavefront.o ConvexDecomposition/raytri.o \ + ConvexDecomposition/concavity.o ConvexDecomposition/splitplane.o \ + ConvexDecomposition/ConvexDecomposition.o ConvexDecomposition/triangulate.o \ + ConvexDecomposition/fitsphere.o ConvexDecomposition/vlookup.o + +HEADERS = \ + ConvexDecomposition/bestfit.h \ + ConvexDecomposition/bestfitobb.h \ + ConvexDecomposition/cd_hull.h \ + ConvexDecomposition/cd_vector.h \ + ConvexDecomposition/cd_wavefront.h \ + ConvexDecomposition/concavity.h \ + ConvexDecomposition/ConvexDecomposition.h \ + ConvexDecomposition/fitsphere.h \ + ConvexDecomposition/float_math.h \ + ConvexDecomposition/meshvolume.h \ + ConvexDecomposition/planetri.h \ + ConvexDecomposition/raytri.h \ + ConvexDecomposition/splitplane.h \ + ConvexDecomposition/triangulate.h \ + ConvexDecomposition/vlookup.h + +CC = g++ + +DEBUG = -ggdb + +CFLAGS = -IConvexDecomposition -Wall -c $(DEBUG) + +LFLAGS = $(DEBUG) + +convex_decomposition: $(OBJS) + $(CC) $(LFLAGS) $(OBJS) -o convex_decomposition + +DecomposeSample.o: DecomposeSample.cpp + $(CC) $(CFLAGS) DecomposeSample.cpp -o $@ + +ConvexDecomposition/bestfit.o: ConvexDecomposition/bestfit.cpp + $(CC) $(CFLAGS) ConvexDecomposition/bestfit.cpp -o $@ + +ConvexDecomposition/bestfitobb.o: ConvexDecomposition/bestfitobb.cpp + $(CC) $(CFLAGS) ConvexDecomposition/bestfitobb.cpp -o $@ + +ConvexDecomposition/cd_hull.o: ConvexDecomposition/cd_hull.cpp + $(CC) $(CFLAGS) ConvexDecomposition/cd_hull.cpp -o $@ + +ConvexDecomposition/cd_wavefront.o: ConvexDecomposition/cd_wavefront.cpp + $(CC) $(CFLAGS) ConvexDecomposition/cd_wavefront.cpp -o $@ + +ConvexDecomposition/concavity.o: ConvexDecomposition/concavity.cpp + $(CC) $(CFLAGS) ConvexDecomposition/concavity.cpp -o $@ + +ConvexDecomposition/ConvexDecomposition.o: ConvexDecomposition/ConvexDecomposition.cpp + $(CC) $(CFLAGS) ConvexDecomposition/ConvexDecomposition.cpp -o $@ + +ConvexDecomposition/fitsphere.o: ConvexDecomposition/fitsphere.cpp + $(CC) $(CFLAGS) ConvexDecomposition/fitsphere.cpp -o $@ + +ConvexDecomposition/float_math.o: ConvexDecomposition/float_math.cpp + $(CC) $(CFLAGS) ConvexDecomposition/float_math.cpp -o $@ + +ConvexDecomposition/meshvolume.o: ConvexDecomposition/meshvolume.cpp + $(CC) $(CFLAGS) ConvexDecomposition/meshvolume.cpp -o $@ + +ConvexDecomposition/planetri.o: ConvexDecomposition/planetri.cpp + $(CC) $(CFLAGS) ConvexDecomposition/planetri.cpp -o $@ + +ConvexDecomposition/raytri.o: ConvexDecomposition/raytri.cpp + $(CC) $(CFLAGS) ConvexDecomposition/raytri.cpp -o $@ + +ConvexDecomposition/splitplane.o: ConvexDecomposition/splitplane.cpp + $(CC) $(CFLAGS) ConvexDecomposition/splitplane.cpp -o $@ + +ConvexDecomposition/triangulate.o: ConvexDecomposition/triangulate.cpp + $(CC) $(CFLAGS) ConvexDecomposition/triangulate.cpp -o $@ + +ConvexDecomposition/vlookup.o: ConvexDecomposition/vlookup.cpp ConvexDecomposition/vlookup.cpp + $(CC) $(CFLAGS) ConvexDecomposition/vlookup.cpp -o $@ + +install: + cp convex_decomposition ../../convex_decomposition/bin/ + +clean: + \rm *.o */*.o convex_decomposition + +tar: + tar cfv ConvexDecomposition.tar DecomposeSample.cpp convex_decomposition Makefile \ + ConvexDecomposition diff --git a/convex_decomposition/ConvexDecomposition/chair.obj b/convex_decomposition/ConvexDecomposition/chair.obj new file mode 100644 index 0000000..eddbcf4 --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/chair.obj @@ -0,0 +1,3083 @@ +v -0.203961 0.754510 0.211019 +v -0.199603 1.785488 -0.001498 +v -0.199163 0.754510 -0.001498 +v -0.199603 1.785488 -0.001498 +v -0.203961 0.754510 0.211019 +v -0.199830 1.524172 0.214066 +v -0.214032 1.655104 0.216193 +v -0.199830 1.524172 0.214066 +v -0.214032 0.738577 0.216193 +v -0.203961 0.754510 0.211019 +v -0.214032 0.738577 0.216193 +v -0.199830 1.524172 0.214066 +v -0.214032 0.738577 0.216193 +v -0.203961 0.754510 0.211019 +v -0.209234 0.738577 -0.001498 +v -0.199163 0.754510 -0.001498 +v -0.209234 0.738577 -0.001498 +v -0.203961 0.754510 0.211019 +v 0.056176 0.210912 -0.001498 +v -0.011230 0.210913 0.215059 +v -0.012112 0.210912 -0.001498 +v 0.057057 0.210913 0.214728 +v -0.012112 0.210912 -0.001498 +v -0.011230 0.275571 0.215059 +v -0.012112 0.275571 -0.001498 +v -0.011230 0.210913 0.215059 +v -0.012112 0.275571 -0.001498 +v 0.057057 0.275571 0.214728 +v 0.056176 0.275571 -0.001498 +v -0.011230 0.275571 0.215059 +v 0.056176 0.275571 -0.001498 +v 0.057057 0.210913 0.214728 +v 0.056176 0.210912 -0.001498 +v 0.057057 0.275571 0.214728 +v 0.057057 0.210913 0.214728 +v -0.146260 0.206221 0.217801 +v -0.011230 0.210913 0.215059 +v -0.146260 0.206221 0.217801 +v 0.057057 0.210913 0.214728 +v 0.182828 0.206221 0.216341 +v -0.011230 0.275571 0.215059 +v 0.182828 0.280263 0.216341 +v 0.057057 0.275571 0.214728 +v 0.182828 0.280263 0.216341 +v -0.011230 0.275571 0.215059 +v -0.146260 0.280263 0.217801 +v -0.011230 0.210913 0.215059 +v -0.146260 0.280263 0.217801 +v -0.011230 0.275571 0.215059 +v -0.146260 0.206221 0.217801 +v 0.057057 0.275571 0.214728 +v 0.182828 0.206221 0.216341 +v 0.057057 0.210913 0.214728 +v 0.182828 0.280263 0.216341 +v -0.146260 0.206221 0.217801 +v 0.181545 0.206221 0.286352 +v -0.147543 0.206221 0.287812 +v 0.182828 0.206221 0.216341 +v -0.147543 0.206221 0.287812 +v 0.181545 0.280263 0.286352 +v -0.147543 0.280263 0.287812 +v 0.181545 0.206221 0.286352 +v -0.147543 0.280263 0.287812 +v 0.182828 0.280263 0.216341 +v -0.146260 0.280263 0.217801 +v 0.181545 0.280263 0.286352 +v -0.208590 -0.001787 0.279676 +v -0.214032 0.243242 0.216341 +v -0.207557 -0.001787 0.223301 +v -0.215315 0.243242 0.286352 +v -0.207557 -0.001787 0.223301 +v -0.146260 0.206221 0.217801 +v -0.152985 -0.001787 0.224477 +v -0.146260 0.206221 0.217801 +v -0.207557 -0.001787 0.223301 +v -0.214032 0.243242 0.216341 +v -0.152985 -0.001787 0.224477 +v -0.147543 0.206221 0.287812 +v -0.154018 -0.001787 0.280852 +v -0.146260 0.206221 0.217801 +v -0.154018 -0.001787 0.280852 +v -0.215315 0.243242 0.286352 +v -0.208590 -0.001787 0.279676 +v -0.215315 0.243242 0.286352 +v -0.154018 -0.001787 0.280852 +v -0.147543 0.206221 0.287812 +v 0.188270 -0.001787 0.279676 +v 0.182828 0.206221 0.216341 +v 0.189303 -0.001787 0.223301 +v 0.181545 0.206221 0.286352 +v 0.189303 -0.001787 0.223301 +v 0.250600 0.243242 0.217801 +v 0.243875 -0.001787 0.224477 +v 0.250600 0.243242 0.217801 +v 0.189303 -0.001787 0.223301 +v 0.182828 0.206221 0.216341 +v 0.243875 -0.001787 0.224477 +v 0.249317 0.243242 0.287812 +v 0.242842 -0.001787 0.280852 +v 0.250600 0.243242 0.217801 +v 0.242842 -0.001787 0.280852 +v 0.181545 0.206221 0.286352 +v 0.188270 -0.001787 0.279676 +v 0.181545 0.206221 0.286352 +v 0.242842 -0.001787 0.280852 +v 0.249317 0.243242 0.287812 +v -0.214032 0.243242 0.216341 +v -0.146260 0.280263 0.217801 +v -0.146260 0.206221 0.217801 +v -0.215315 0.243242 0.286352 +v -0.147543 0.206221 0.287812 +v -0.147543 0.280263 0.287812 +v 0.250600 0.243242 0.217801 +v 0.182828 0.206221 0.216341 +v 0.182828 0.280263 0.216341 +v 0.249317 0.243242 0.287812 +v 0.181545 0.280263 0.286352 +v 0.181545 0.206221 0.286352 +v -0.215315 0.243242 0.286352 +v -0.214032 0.377162 0.216341 +v -0.214032 0.243242 0.216341 +v -0.147543 0.280263 0.287812 +v -0.146260 0.280263 0.217801 +v -0.146260 0.377162 0.217801 +v 0.181545 0.280263 0.286352 +v 0.182828 0.377162 0.216341 +v 0.182828 0.280263 0.216341 +v 0.249317 0.243242 0.287812 +v 0.250600 0.243242 0.217801 +v 0.250600 0.377162 0.217801 +v 0.250600 0.377162 0.217801 +v 0.182828 0.377162 0.216341 +v -0.146260 0.377162 0.217801 +v -0.214032 0.377162 0.216341 +v -0.128461 1.675364 -0.001498 +v -0.146260 1.508024 0.217653 +v -0.132386 1.472782 0.176497 +v -0.146260 1.508024 0.217653 +v -0.128461 1.675364 -0.001498 +v -0.141462 1.768750 -0.001498 +v -0.132386 0.781150 0.176497 +v -0.141462 0.738577 -0.001498 +v -0.128461 0.781150 -0.001498 +v -0.146260 0.738577 0.217653 +v -0.132386 1.472782 0.176497 +v -0.146260 0.738577 0.217653 +v -0.132386 0.781150 0.176497 +v -0.146260 1.508024 0.217653 +v -0.160112 1.524172 0.214922 +v -0.141462 1.768750 -0.001498 +v -0.159884 1.785488 -0.001498 +v -0.141462 1.768750 -0.001498 +v -0.160112 1.524172 0.214922 +v -0.146260 1.508024 0.217653 +v -0.128461 0.781150 -0.001498 +v -0.128461 1.675364 -0.001498 +v -0.132386 0.781150 0.176497 +v -0.132386 1.472782 0.176497 +v -0.174244 1.836233 0.258962 +v -0.187331 1.836233 0.244894 +v -0.187584 1.836233 0.258675 +v -0.173991 1.836233 0.245182 +v -0.160446 1.785009 0.231735 +v -0.174244 1.836233 0.258962 +v -0.161202 1.785009 0.272981 +v -0.173991 1.836233 0.245182 +v -0.200373 1.785009 0.230875 +v -0.173991 1.836233 0.245182 +v -0.160446 1.785009 0.231735 +v -0.187331 1.836233 0.244894 +v -0.201129 1.785009 0.272121 +v -0.187331 1.836233 0.244894 +v -0.200373 1.785009 0.230875 +v -0.187584 1.836233 0.258675 +v -0.161202 1.785009 0.272981 +v -0.187584 1.836233 0.258675 +v -0.201129 1.785009 0.272121 +v -0.174244 1.836233 0.258962 +v -0.137050 1.756645 0.235571 +v -0.195826 1.756645 0.206731 +v -0.224525 1.756645 0.268286 +v -0.165749 1.756645 0.297125 +v -0.137050 1.756645 0.235571 +v -0.137050 1.715855 0.235571 +v -0.164105 1.756645 0.207415 +v -0.164105 1.715855 0.207415 +v -0.195826 1.756645 0.206731 +v -0.195826 1.715855 0.206731 +v -0.223891 1.756645 0.233700 +v -0.223891 1.715855 0.233700 +v -0.165749 1.756645 0.297125 +v -0.165749 1.715855 0.297125 +v -0.137684 1.756645 0.270157 +v -0.137684 1.715855 0.270157 +v -0.224525 1.756645 0.268286 +v -0.224525 1.715855 0.268286 +v -0.197470 1.756645 0.296441 +v -0.197470 1.715855 0.296441 +v -0.161841 1.691613 0.233120 +v -0.137684 1.715855 0.270157 +v -0.162545 1.691613 0.271537 +v -0.199030 1.691613 0.232319 +v -0.164105 1.715855 0.207415 +v -0.161841 1.691613 0.233120 +v -0.199734 1.691613 0.270736 +v -0.223891 1.715855 0.233700 +v -0.199030 1.691613 0.232319 +v -0.162545 1.691613 0.271537 +v -0.197470 1.715855 0.296441 +v -0.199734 1.691613 0.270736 +v -0.137684 1.756645 0.270157 +v -0.164105 1.756645 0.207415 +v -0.223891 1.756645 0.233700 +v -0.197470 1.756645 0.296441 +v -0.137050 1.715855 0.235571 +v -0.195826 1.715855 0.206731 +v -0.224525 1.715855 0.268286 +v -0.165749 1.715855 0.297125 +v -0.161202 1.785009 0.272981 +v -0.160446 1.785009 0.231735 +v -0.201129 1.785009 0.272121 +v -0.200373 1.785009 0.230875 +v -0.162545 1.691613 0.271537 +v -0.161841 1.691613 0.233120 +v -0.199734 1.691613 0.270736 +v -0.199030 1.691613 0.232319 +v -0.162545 1.691613 0.271537 +v -0.161841 1.668882 0.233120 +v -0.161841 1.691613 0.233120 +v -0.162545 1.668882 0.271537 +v -0.161841 1.691613 0.233120 +v -0.199030 1.668882 0.232319 +v -0.199030 1.691613 0.232319 +v -0.161841 1.668882 0.233120 +v -0.199030 1.691613 0.232319 +v -0.199734 1.668882 0.270736 +v -0.199734 1.691613 0.270736 +v -0.199030 1.668882 0.232319 +v -0.199734 1.691613 0.270736 +v -0.162545 1.668882 0.271537 +v -0.162545 1.691613 0.271537 +v -0.199734 1.668882 0.270736 +v -0.161841 1.668882 0.233120 +v -0.214032 1.655104 0.216193 +v -0.199030 1.668882 0.232319 +v -0.146260 1.655104 0.217653 +v -0.162545 1.668882 0.271537 +v -0.146260 1.655104 0.217653 +v -0.161841 1.668882 0.233120 +v -0.147543 1.655104 0.287664 +v -0.199734 1.668882 0.270736 +v -0.147543 1.655104 0.287664 +v -0.162545 1.668882 0.271537 +v -0.215315 1.655104 0.286203 +v -0.199030 1.668882 0.232319 +v -0.215315 1.655104 0.286203 +v -0.199734 1.668882 0.270736 +v -0.214032 1.655104 0.216193 +v -0.159884 1.900273 -0.001498 +v -0.160112 1.524172 0.214922 +v -0.159884 1.785488 -0.001498 +v -0.160112 1.638956 0.214922 +v -0.199603 1.785488 -0.001498 +v -0.199830 1.638956 0.214066 +v -0.199603 1.900273 -0.001498 +v -0.199830 1.524172 0.214066 +v -0.199603 1.900273 -0.001498 +v -0.160112 1.638956 0.214922 +v -0.159884 1.900273 -0.001498 +v -0.160112 1.638956 0.214922 +v -0.199603 1.900273 -0.001498 +v -0.199830 1.638956 0.214066 +v -0.160112 1.638956 0.214922 +v -0.146260 1.508024 0.217653 +v -0.160112 1.524172 0.214922 +v -0.146260 1.655104 0.217653 +v -0.199830 1.638956 0.214066 +v -0.146260 1.655104 0.217653 +v -0.160112 1.638956 0.214922 +v -0.214032 1.655104 0.216193 +v -0.199830 1.638956 0.214066 +v -0.147543 1.655104 0.287664 +v -0.146260 1.508024 0.217653 +v -0.146260 1.655104 0.217653 +v -0.141462 0.738577 -0.001498 +v -0.146260 0.683386 0.217653 +v -0.141462 0.682417 -0.001498 +v -0.146260 0.738577 0.217653 +v -0.209234 0.682417 -0.001498 +v -0.214032 0.738577 0.216193 +v -0.209234 0.738577 -0.001498 +v -0.214032 0.683393 0.216193 +v -0.141462 0.682417 -0.001498 +v -0.214032 0.683393 0.216193 +v -0.209234 0.682417 -0.001498 +v -0.146260 0.683386 0.217653 +v -0.146260 0.738577 0.217653 +v -0.147543 0.738577 0.287664 +v -0.215315 1.655104 0.286203 +v -0.147543 0.738577 0.287664 +v -0.147543 1.655104 0.287664 +v -0.215315 0.710897 0.286203 +v -0.214032 1.655104 0.216193 +v -0.215315 0.710897 0.286203 +v -0.215315 1.655104 0.286203 +v -0.214032 0.738577 0.216193 +v -0.213681 0.377162 -0.001498 +v -0.214032 0.456870 0.216341 +v -0.213680 0.456870 -0.001498 +v -0.214032 0.377162 0.216341 +v -0.213680 0.456870 -0.001498 +v -0.231718 0.471319 0.172684 +v -0.231718 0.471319 -0.001498 +v -0.214032 0.456870 0.216341 +v 0.261861 0.726253 0.301147 +v -0.147543 0.738577 0.287664 +v -0.134999 0.726253 0.301147 +v 0.245288 0.738577 0.287664 +v -0.133232 0.726253 0.204720 +v 0.246571 0.738577 0.217653 +v 0.263628 0.726253 0.204720 +v -0.146260 0.738577 0.217653 +v -0.133232 0.690088 0.204720 +v -0.146260 0.683386 0.217653 +v -0.147543 0.683217 0.287664 +v -0.134999 0.690088 0.301147 +v -0.147543 0.683217 0.287664 +v -0.214032 0.683393 0.216193 +v 0.263628 0.690088 0.204720 +v 0.261861 0.690088 0.301147 +v 0.261861 0.690088 0.301147 +v 0.249317 0.683217 0.287664 +v 0.250600 0.683217 0.217653 +v 0.263628 0.690088 0.204720 +v 0.249317 0.683217 0.287664 +v -0.147543 0.609148 0.288033 +v 0.181545 0.609148 0.286573 +v -0.147543 0.609148 0.288033 +v 0.249317 0.683217 0.287664 +v -0.147543 0.683217 0.287664 +v 0.182828 0.608985 0.216563 +v -0.146260 0.683386 0.217653 +v 0.250600 0.683217 0.217653 +v -0.146260 0.683386 0.217653 +v 0.182828 0.608985 0.216563 +v -0.146260 0.608985 0.218023 +v 0.181545 0.609148 0.286573 +v -0.146260 0.608985 0.218023 +v 0.182828 0.608985 0.216563 +v -0.147543 0.609148 0.288033 +v 0.261861 0.726253 0.301147 +v -0.215315 0.710897 0.286203 +v -0.147543 0.609148 0.288033 +v -0.147543 0.683217 0.287664 +v -0.214032 0.683393 0.216193 +v -0.146260 0.683386 0.217653 +v -0.146260 0.608985 0.218023 +v -0.214032 0.456870 0.216341 +v -0.146260 0.456870 0.217801 +v -0.147543 0.609148 0.288033 +v -0.146260 0.608985 0.218023 +v -0.215315 0.710897 0.286203 +v -0.147543 0.280263 0.287812 +v -0.147543 0.609148 0.288033 +v -0.214032 0.456870 0.216341 +v -0.146260 0.608985 0.218023 +v -0.146260 0.456870 0.217801 +v -0.146260 0.608985 0.218023 +v -0.214032 0.456870 0.216341 +v -0.214032 0.683393 0.216193 +v -0.152985 -0.001787 0.224477 +v -0.208590 -0.001787 0.279676 +v -0.207557 -0.001787 0.223301 +v -0.154018 -0.001787 0.280852 +v 0.250600 0.683217 0.217653 +v 0.249317 0.683217 0.287664 +v 0.182828 0.608985 0.216563 +v 0.182828 0.456870 0.216341 +v 0.181545 0.609148 0.286573 +v 0.250600 0.456870 0.217801 +v 0.249317 0.683217 0.287664 +v 0.250600 0.683217 0.217653 +v 0.181545 0.609148 0.286573 +v 0.181545 0.609148 0.286573 +v 0.249317 0.243242 0.287812 +v 0.249317 0.683217 0.287664 +v 0.182828 0.456870 0.216341 +v 0.250600 0.683217 0.217653 +v 0.250600 0.456870 0.217801 +v 0.250600 0.683217 0.217653 +v 0.182828 0.456870 0.216341 +v 0.182828 0.608985 0.216563 +v 0.243875 -0.001787 0.224477 +v 0.188270 -0.001787 0.279676 +v 0.189303 -0.001787 0.223301 +v 0.242842 -0.001787 0.280852 +v 0.250600 0.377162 0.217801 +v 0.247841 0.456870 -0.001498 +v 0.250600 0.456870 0.217801 +v 0.247847 0.377162 -0.001498 +v -0.146260 0.456870 0.217801 +v 0.182828 0.377162 0.216341 +v 0.182828 0.456870 0.216341 +v -0.146260 0.377162 0.217801 +v 0.247841 0.456870 -0.001498 +v 0.262209 0.471319 0.172684 +v 0.250600 0.456870 0.217801 +v 0.262209 0.471319 -0.001498 +v -0.231718 0.520293 -0.001498 +v -0.231718 0.520293 0.172684 +v -0.223747 0.491776 0.204447 +v -0.163649 0.564918 -0.001498 +v -0.163649 0.564918 0.172684 +v 0.199481 0.564918 -0.001498 +v 0.199481 0.564918 0.172684 +v 0.262209 0.520293 -0.001498 +v 0.262209 0.520293 0.172684 +v -0.163649 0.522718 0.208096 +v 0.199480 0.522718 0.208096 +v 0.261171 0.491776 0.208368 +v 0.262209 0.520293 -0.001498 +v 0.261171 0.491776 0.208368 +v 0.247847 0.377162 -0.001498 +v 0.182828 0.377162 0.216341 +v 0.182828 0.377162 -0.001498 +v 0.250600 0.377162 0.217801 +v -0.147984 0.377162 -0.001498 +v 0.182828 0.377162 0.216341 +v -0.146260 0.377162 0.217801 +v 0.182828 0.377162 -0.001498 +v -0.147984 0.377162 -0.001498 +v -0.214032 0.377162 0.216341 +v -0.213681 0.377162 -0.001498 +v -0.146260 0.377162 0.217801 +v 0.182828 0.456870 0.216341 +v 0.250600 0.456870 0.217801 +v -0.146260 0.456870 0.217801 +v -0.214032 0.456870 0.216341 +v -0.203961 0.754510 -0.214016 +v -0.199163 0.754510 -0.001498 +v -0.199603 1.785488 -0.001498 +v -0.199603 1.785488 -0.001498 +v -0.199830 1.524172 -0.217063 +v -0.203961 0.754510 -0.214016 +v -0.214032 1.655105 -0.219189 +v -0.214032 0.738577 -0.219189 +v -0.199830 1.524172 -0.217063 +v -0.203961 0.754510 -0.214016 +v -0.199830 1.524172 -0.217063 +v -0.214032 0.738577 -0.219189 +v -0.214032 0.738577 -0.219189 +v -0.209234 0.738577 -0.001498 +v -0.203961 0.754510 -0.214016 +v -0.199163 0.754510 -0.001498 +v -0.203961 0.754510 -0.214016 +v -0.209234 0.738577 -0.001498 +v -0.011230 0.210913 -0.218055 +v 0.057057 0.210913 -0.217724 +v -0.012112 0.210912 -0.001498 +v -0.012112 0.275571 -0.001498 +v -0.011230 0.275571 -0.218055 +v -0.011230 0.210913 -0.218055 +v 0.057057 0.275571 -0.217724 +v -0.011230 0.275571 -0.218055 +v 0.056176 0.275571 -0.001498 +v 0.056176 0.210912 -0.001498 +v 0.057057 0.210913 -0.217724 +v 0.057057 0.275571 -0.217724 +v 0.057057 0.210913 -0.217724 +v -0.011230 0.210913 -0.218055 +v -0.146260 0.206221 -0.220798 +v -0.146260 0.206221 -0.220798 +v 0.182828 0.206221 -0.219337 +v 0.057057 0.210913 -0.217724 +v -0.011230 0.275571 -0.218055 +v 0.057057 0.275571 -0.217724 +v 0.182828 0.280263 -0.219337 +v 0.182828 0.280263 -0.219337 +v -0.146260 0.280263 -0.220798 +v -0.011230 0.275571 -0.218055 +v -0.011230 0.210913 -0.218055 +v -0.011230 0.275571 -0.218055 +v -0.146260 0.280263 -0.220798 +v -0.146260 0.206221 -0.220798 +v 0.057057 0.275571 -0.217724 +v 0.057057 0.210913 -0.217724 +v 0.182828 0.206221 -0.219337 +v 0.182828 0.280263 -0.219337 +v -0.146260 0.206221 -0.220798 +v -0.147543 0.206221 -0.290808 +v 0.181545 0.206221 -0.289348 +v 0.182828 0.206221 -0.219337 +v -0.147543 0.206221 -0.290808 +v -0.147543 0.280263 -0.290808 +v 0.181545 0.280263 -0.289348 +v 0.181545 0.206221 -0.289348 +v -0.147543 0.280263 -0.290808 +v -0.146260 0.280263 -0.220798 +v 0.182828 0.280263 -0.219337 +v 0.181545 0.280263 -0.289348 +v -0.208590 -0.001787 -0.282672 +v -0.207557 -0.001787 -0.226297 +v -0.214032 0.243242 -0.219337 +v -0.215315 0.243242 -0.289348 +v -0.207557 -0.001787 -0.226297 +v -0.152985 -0.001787 -0.227473 +v -0.146260 0.206221 -0.220798 +v -0.146260 0.206221 -0.220798 +v -0.214032 0.243242 -0.219337 +v -0.207557 -0.001787 -0.226297 +v -0.152985 -0.001787 -0.227473 +v -0.154018 -0.001787 -0.283848 +v -0.147543 0.206221 -0.290808 +v -0.146260 0.206221 -0.220798 +v -0.154018 -0.001787 -0.283848 +v -0.208590 -0.001787 -0.282672 +v -0.215315 0.243242 -0.289348 +v -0.215315 0.243242 -0.289348 +v -0.147543 0.206221 -0.290808 +v -0.154018 -0.001787 -0.283848 +v 0.188270 -0.001787 -0.282672 +v 0.189303 -0.001787 -0.226297 +v 0.182828 0.206221 -0.219337 +v 0.181545 0.206221 -0.289348 +v 0.189303 -0.001787 -0.226297 +v 0.243875 -0.001787 -0.227473 +v 0.250600 0.243242 -0.220798 +v 0.250600 0.243242 -0.220798 +v 0.182828 0.206221 -0.219337 +v 0.189303 -0.001787 -0.226297 +v 0.243875 -0.001787 -0.227473 +v 0.242842 -0.001787 -0.283848 +v 0.249317 0.243242 -0.290808 +v 0.250600 0.243242 -0.220798 +v 0.242842 -0.001787 -0.283848 +v 0.188270 -0.001787 -0.282672 +v 0.181545 0.206221 -0.289348 +v 0.181545 0.206221 -0.289348 +v 0.249317 0.243242 -0.290808 +v 0.242842 -0.001787 -0.283848 +v -0.214032 0.243242 -0.219337 +v -0.146260 0.206221 -0.220798 +v -0.146260 0.280263 -0.220798 +v -0.215315 0.243242 -0.289348 +v -0.147543 0.280263 -0.290808 +v -0.147543 0.206221 -0.290808 +v 0.250600 0.243242 -0.220798 +v 0.182828 0.280263 -0.219337 +v 0.182828 0.206221 -0.219337 +v 0.249317 0.243242 -0.290808 +v 0.181545 0.206221 -0.289348 +v 0.181545 0.280263 -0.289348 +v -0.215315 0.243242 -0.289348 +v -0.214032 0.243242 -0.219337 +v -0.214032 0.377162 -0.219337 +v -0.147543 0.280263 -0.290808 +v -0.146260 0.377162 -0.220798 +v -0.146260 0.280263 -0.220798 +v 0.181545 0.280263 -0.289348 +v 0.182828 0.280263 -0.219337 +v 0.182828 0.377162 -0.219337 +v 0.249317 0.243242 -0.290808 +v 0.250600 0.377162 -0.220798 +v 0.250600 0.243242 -0.220798 +v 0.250600 0.377162 -0.220798 +v 0.182828 0.377162 -0.219337 +v -0.146260 0.377162 -0.220798 +v -0.214032 0.377162 -0.219337 +v -0.128461 1.675364 -0.001498 +v -0.132386 1.472782 -0.179493 +v -0.146260 1.508024 -0.220649 +v -0.146260 1.508024 -0.220649 +v -0.141462 1.768750 -0.001498 +v -0.128461 1.675364 -0.001498 +v -0.132386 0.781150 -0.179493 +v -0.128461 0.781150 -0.001498 +v -0.141462 0.738577 -0.001498 +v -0.146260 0.738577 -0.220649 +v -0.132386 1.472782 -0.179493 +v -0.132386 0.781150 -0.179493 +v -0.146260 0.738577 -0.220649 +v -0.146260 1.508024 -0.220649 +v -0.160112 1.524172 -0.217918 +v -0.159884 1.785488 -0.001498 +v -0.141462 1.768750 -0.001498 +v -0.141462 1.768750 -0.001498 +v -0.146260 1.508024 -0.220649 +v -0.160112 1.524172 -0.217918 +v -0.128461 0.781150 -0.001498 +v -0.132386 0.781150 -0.179493 +v -0.128461 1.675364 -0.001498 +v -0.132386 1.472782 -0.179493 +v -0.174244 1.836233 -0.261959 +v -0.187584 1.836233 -0.261671 +v -0.187331 1.836233 -0.247891 +v -0.173991 1.836233 -0.248178 +v -0.160446 1.785009 -0.234732 +v -0.161202 1.785009 -0.275978 +v -0.174244 1.836233 -0.261959 +v -0.173991 1.836233 -0.248178 +v -0.200373 1.785009 -0.233871 +v -0.160446 1.785009 -0.234732 +v -0.173991 1.836233 -0.248178 +v -0.187331 1.836233 -0.247891 +v -0.201129 1.785009 -0.275117 +v -0.200373 1.785009 -0.233871 +v -0.187331 1.836233 -0.247891 +v -0.187584 1.836233 -0.261671 +v -0.161202 1.785009 -0.275978 +v -0.201129 1.785009 -0.275117 +v -0.187584 1.836233 -0.261671 +v -0.174244 1.836233 -0.261959 +v -0.137050 1.756645 -0.238567 +v -0.195826 1.756645 -0.209728 +v -0.224525 1.756645 -0.271282 +v -0.165749 1.756645 -0.300121 +v -0.137050 1.756645 -0.238567 +v -0.164105 1.756645 -0.210411 +v -0.137050 1.715855 -0.238567 +v -0.164105 1.715855 -0.210411 +v -0.195826 1.756645 -0.209728 +v -0.223891 1.756645 -0.236696 +v -0.195826 1.715855 -0.209728 +v -0.223891 1.715855 -0.236696 +v -0.165749 1.756645 -0.300121 +v -0.137684 1.756645 -0.273153 +v -0.165749 1.715855 -0.300121 +v -0.137684 1.715855 -0.273153 +v -0.224525 1.756645 -0.271282 +v -0.197470 1.756645 -0.299438 +v -0.224525 1.715855 -0.271282 +v -0.197470 1.715855 -0.299438 +v -0.161841 1.691613 -0.236117 +v -0.162545 1.691613 -0.274534 +v -0.137684 1.715855 -0.273153 +v -0.199030 1.691613 -0.235315 +v -0.161841 1.691613 -0.236117 +v -0.164105 1.715855 -0.210411 +v -0.199734 1.691613 -0.273733 +v -0.199030 1.691613 -0.235315 +v -0.223891 1.715855 -0.236696 +v -0.162545 1.691613 -0.274534 +v -0.199734 1.691613 -0.273733 +v -0.197470 1.715855 -0.299438 +v -0.137684 1.756645 -0.273153 +v -0.164105 1.756645 -0.210411 +v -0.223891 1.756645 -0.236696 +v -0.197470 1.756645 -0.299438 +v -0.137050 1.715855 -0.238567 +v -0.195826 1.715855 -0.209728 +v -0.224525 1.715855 -0.271282 +v -0.165749 1.715855 -0.300121 +v -0.161202 1.785009 -0.275978 +v -0.160446 1.785009 -0.234732 +v -0.201129 1.785009 -0.275117 +v -0.200373 1.785009 -0.233871 +v -0.162545 1.691613 -0.274534 +v -0.161841 1.691613 -0.236117 +v -0.199734 1.691613 -0.273733 +v -0.199030 1.691613 -0.235315 +v -0.162545 1.691613 -0.274534 +v -0.161841 1.691613 -0.236117 +v -0.161841 1.668882 -0.236117 +v -0.162545 1.668882 -0.274534 +v -0.161841 1.691613 -0.236117 +v -0.199030 1.691613 -0.235315 +v -0.199030 1.668882 -0.235315 +v -0.161841 1.668882 -0.236117 +v -0.199030 1.691613 -0.235315 +v -0.199734 1.691613 -0.273733 +v -0.199734 1.668882 -0.273733 +v -0.199030 1.668882 -0.235315 +v -0.199734 1.691613 -0.273733 +v -0.162545 1.691613 -0.274534 +v -0.162545 1.668882 -0.274534 +v -0.199734 1.668882 -0.273733 +v -0.161841 1.668882 -0.236117 +v -0.199030 1.668882 -0.235315 +v -0.214032 1.655105 -0.219189 +v -0.146260 1.655105 -0.220649 +v -0.162545 1.668882 -0.274534 +v -0.161841 1.668882 -0.236117 +v -0.146260 1.655105 -0.220649 +v -0.147543 1.655105 -0.290660 +v -0.199734 1.668882 -0.273733 +v -0.162545 1.668882 -0.274534 +v -0.147543 1.655105 -0.290660 +v -0.215315 1.655105 -0.289200 +v -0.199030 1.668882 -0.235315 +v -0.199734 1.668882 -0.273733 +v -0.215315 1.655105 -0.289200 +v -0.214032 1.655105 -0.219189 +v -0.159884 1.900273 -0.001498 +v -0.159884 1.785488 -0.001498 +v -0.160112 1.524172 -0.217918 +v -0.160112 1.638956 -0.217918 +v -0.199603 1.785488 -0.001498 +v -0.199603 1.900273 -0.001498 +v -0.199830 1.638956 -0.217063 +v -0.199830 1.524172 -0.217063 +v -0.199603 1.900273 -0.001498 +v -0.159884 1.900273 -0.001498 +v -0.160112 1.638956 -0.217918 +v -0.160112 1.638956 -0.217918 +v -0.199830 1.638956 -0.217063 +v -0.199603 1.900273 -0.001498 +v -0.160112 1.638956 -0.217918 +v -0.160112 1.524172 -0.217918 +v -0.146260 1.508024 -0.220649 +v -0.146260 1.655105 -0.220649 +v -0.199830 1.638956 -0.217063 +v -0.160112 1.638956 -0.217918 +v -0.146260 1.655105 -0.220649 +v -0.214032 1.655105 -0.219189 +v -0.199830 1.638956 -0.217063 +v -0.147543 1.655105 -0.290660 +v -0.146260 1.655105 -0.220649 +v -0.146260 1.508024 -0.220649 +v -0.141462 0.738577 -0.001498 +v -0.141462 0.682417 -0.001498 +v -0.146260 0.683386 -0.220649 +v -0.146260 0.738577 -0.220649 +v -0.209234 0.682417 -0.001498 +v -0.209234 0.738577 -0.001498 +v -0.214032 0.738577 -0.219189 +v -0.214032 0.683393 -0.219189 +v -0.141462 0.682417 -0.001498 +v -0.209234 0.682417 -0.001498 +v -0.214032 0.683393 -0.219189 +v -0.146260 0.683386 -0.220649 +v -0.146260 0.738577 -0.220649 +v -0.147543 0.738577 -0.290660 +v -0.215315 1.655105 -0.289200 +v -0.147543 1.655105 -0.290660 +v -0.147543 0.738577 -0.290660 +v -0.215315 0.710897 -0.289200 +v -0.214032 1.655105 -0.219189 +v -0.215315 1.655105 -0.289200 +v -0.215315 0.710897 -0.289200 +v -0.214032 0.738577 -0.219189 +v -0.213681 0.377162 -0.001498 +v -0.213680 0.456870 -0.001498 +v -0.214032 0.456870 -0.219337 +v -0.214032 0.377162 -0.219337 +v -0.231718 0.471319 -0.175680 +v -0.214032 0.456870 -0.219337 +v 0.261861 0.726253 -0.304144 +v -0.134999 0.726253 -0.304144 +v -0.147543 0.738577 -0.290660 +v 0.245288 0.738577 -0.290660 +v -0.133232 0.726253 -0.207717 +v 0.263628 0.726253 -0.207717 +v 0.246571 0.738577 -0.220649 +v -0.146260 0.738577 -0.220649 +v -0.133232 0.690088 -0.207717 +v -0.146260 0.683386 -0.220649 +v -0.134999 0.690088 -0.304144 +v -0.147543 0.683217 -0.290660 +v -0.147543 0.683217 -0.290660 +v -0.214032 0.683393 -0.219189 +v 0.263628 0.690088 -0.207717 +v 0.261861 0.690088 -0.304144 +v 0.261861 0.690088 -0.304144 +v 0.249317 0.683217 -0.290660 +v 0.250600 0.683217 -0.220649 +v 0.263628 0.690088 -0.207717 +v 0.249317 0.683217 -0.290660 +v 0.181545 0.609149 -0.289570 +v -0.147543 0.609149 -0.291030 +v -0.147543 0.609149 -0.291030 +v -0.147543 0.683217 -0.290660 +v 0.249317 0.683217 -0.290660 +v 0.182828 0.608985 -0.219559 +v 0.250600 0.683217 -0.220649 +v -0.146260 0.683386 -0.220649 +v -0.146260 0.683386 -0.220649 +v -0.146260 0.608985 -0.221019 +v 0.182828 0.608985 -0.219559 +v 0.181545 0.609149 -0.289570 +v 0.182828 0.608985 -0.219559 +v -0.146260 0.608985 -0.221019 +v -0.147543 0.609149 -0.291030 +v 0.261861 0.726253 -0.304144 +v -0.215315 0.710897 -0.289200 +v -0.147543 0.683217 -0.290660 +v -0.147543 0.609149 -0.291030 +v -0.214032 0.683393 -0.219189 +v -0.146260 0.608985 -0.221019 +v -0.146260 0.683386 -0.220649 +v -0.214032 0.456870 -0.219337 +v -0.146260 0.456870 -0.220798 +v -0.147543 0.609149 -0.291030 +v -0.146260 0.608985 -0.221019 +v -0.215315 0.710897 -0.289200 +v -0.147543 0.609149 -0.291030 +v -0.147543 0.280263 -0.290808 +v -0.214032 0.456870 -0.219337 +v -0.146260 0.456870 -0.220798 +v -0.146260 0.608985 -0.221019 +v -0.146260 0.608985 -0.221019 +v -0.214032 0.683393 -0.219189 +v -0.214032 0.456870 -0.219337 +v -0.152985 -0.001787 -0.227473 +v -0.207557 -0.001787 -0.226297 +v -0.208590 -0.001787 -0.282672 +v -0.154018 -0.001787 -0.283848 +v 0.250600 0.683217 -0.220649 +v 0.249317 0.683217 -0.290660 +v 0.182828 0.456870 -0.219337 +v 0.182828 0.608985 -0.219559 +v 0.181545 0.609149 -0.289570 +v 0.250600 0.456870 -0.220798 +v 0.249317 0.683217 -0.290660 +v 0.250600 0.683217 -0.220649 +v 0.181545 0.609149 -0.289570 +v 0.181545 0.609149 -0.289570 +v 0.249317 0.683217 -0.290660 +v 0.249317 0.243242 -0.290808 +v 0.182828 0.456870 -0.219337 +v 0.250600 0.456870 -0.220798 +v 0.250600 0.683217 -0.220649 +v 0.250600 0.683217 -0.220649 +v 0.182828 0.608985 -0.219559 +v 0.182828 0.456870 -0.219337 +v 0.243875 -0.001787 -0.227473 +v 0.189303 -0.001787 -0.226297 +v 0.188270 -0.001787 -0.282672 +v 0.242842 -0.001787 -0.283848 +v 0.250600 0.377162 -0.220798 +v 0.250600 0.456870 -0.220798 +v 0.247841 0.456870 -0.001498 +v 0.247847 0.377162 -0.001498 +v -0.146260 0.456870 -0.220798 +v 0.182828 0.456870 -0.219337 +v 0.182828 0.377162 -0.219337 +v -0.146260 0.377162 -0.220798 +v 0.250600 0.456870 -0.220798 +v 0.262209 0.471319 -0.175680 +v -0.231718 0.520293 -0.175680 +v -0.223747 0.491776 -0.207443 +v -0.163649 0.564918 -0.175680 +v 0.199481 0.564918 -0.175680 +v 0.262209 0.520293 -0.175680 +v -0.163649 0.522718 -0.211092 +v 0.199480 0.522718 -0.211092 +v 0.261171 0.491776 -0.211365 +v 0.261171 0.491776 -0.211365 +v 0.182828 0.377162 -0.219337 +v 0.250600 0.377162 -0.220798 +v -0.146260 0.377162 -0.220798 +v 0.182828 0.377162 -0.219337 +v -0.214032 0.377162 -0.219337 +v -0.146260 0.377162 -0.220798 +v 0.182828 0.456870 -0.219337 +v 0.250600 0.456870 -0.220798 +v -0.146260 0.456870 -0.220798 +v -0.214032 0.456870 -0.219337 +vt 0.674120 0.126945 +vt 0.132117 0.022442 +vt 0.673842 0.014528 +vt 0.132117 0.022442 +vt 0.674120 0.126945 +vt 0.269444 0.134379 +vt 0.201464 0.137566 +vt 0.269444 0.134379 +vt 0.683074 0.130257 +vt 0.674120 0.126945 +vt 0.683074 0.130257 +vt 0.269444 0.134379 +vt 0.683074 0.130257 +vt 0.674120 0.126945 +vt 0.682797 0.015131 +vt 0.673842 0.014528 +vt 0.682797 0.015131 +vt 0.674120 0.126945 +vt 0.448731 0.911043 +vt 0.647034 0.813468 +vt 0.498266 0.960933 +vt 0.597499 0.763578 +vt 0.448555 0.914611 +vt 0.640803 0.812643 +vt 0.492025 0.958847 +vt 0.597333 0.768407 +vt 0.448058 0.911847 +vt 0.647261 0.815930 +vt 0.497076 0.962245 +vt 0.598243 0.765532 +vt 0.450490 0.915256 +vt 0.641027 0.814195 +vt 0.493574 0.959098 +vt 0.597944 0.770354 +vt 0.597499 0.763578 +vt 0.747627 0.909508 +vt 0.647034 0.813468 +vt 0.747627 0.909508 +vt 0.597499 0.763578 +vt 0.509004 0.668989 +vt 0.598243 0.765532 +vt 0.740284 0.906069 +vt 0.647261 0.815930 +vt 0.740284 0.906069 +vt 0.598243 0.765532 +vt 0.503965 0.663285 +vt 0.537299 0.923005 +vt 0.592736 0.752811 +vt 0.483584 0.868868 +vt 0.654247 0.814805 +vt 0.483852 0.865836 +vt 0.647222 0.820979 +vt 0.537044 0.920488 +vt 0.586311 0.758396 +vt 0.747627 0.909508 +vt 0.558029 0.622664 +vt 0.796653 0.863183 +vt 0.509004 0.668989 +vt 0.539725 0.992216 +vt 0.648299 0.813382 +vt 0.505456 0.956870 +vt 0.682568 0.847951 +vt 0.551186 0.615030 +vt 0.740284 0.906069 +vt 0.503965 0.663285 +vt 0.787505 0.857813 +vt 0.952233 0.985260 +vt 0.851318 0.814006 +vt 0.984205 0.954259 +vt 0.811612 0.852504 +vt 0.870723 0.945112 +vt 0.646616 0.821792 +vt 0.825025 0.990459 +vt 0.646616 0.821792 +vt 0.870723 0.945112 +vt 0.672612 0.734479 +vt 0.829209 0.987755 +vt 0.705926 0.772152 +vt 0.869365 0.948108 +vt 0.655721 0.820941 +vt 0.955599 0.990783 +vt 0.853394 0.818481 +vt 0.986451 0.960183 +vt 0.853394 0.818481 +vt 0.955599 0.990783 +vt 0.835786 0.877370 +vt 0.869526 0.947996 +vt 0.655999 0.821124 +vt 0.829184 0.987657 +vt 0.706294 0.772244 +vt 0.823909 0.991444 +vt 0.674064 0.733928 +vt 0.870047 0.946545 +vt 0.674064 0.733928 +vt 0.823909 0.991444 +vt 0.647222 0.820979 +vt 0.828978 0.987744 +vt 0.701503 0.767118 +vt 0.869469 0.947964 +vt 0.651218 0.816520 +vt 0.807277 0.916486 +vt 0.682568 0.847951 +vt 0.781732 0.941795 +vt 0.682568 0.847951 +vt 0.807277 0.916486 +vt 0.697157 0.799236 +vt 0.672612 0.734479 +vt 0.585106 0.759798 +vt 0.646616 0.821792 +vt 0.853394 0.818481 +vt 0.835786 0.877370 +vt 0.794376 0.835595 +vt 0.674064 0.733928 +vt 0.647222 0.820979 +vt 0.586311 0.758396 +vt 0.697157 0.799236 +vt 0.648299 0.813382 +vt 0.682568 0.847951 +vt 0.811612 0.852504 +vt 0.776596 0.738943 +vt 0.851318 0.814006 +vt 0.647622 0.712276 +vt 0.597460 0.761549 +vt 0.521957 0.684769 +vt 0.647484 0.712183 +vt 0.521525 0.684603 +vt 0.597115 0.761577 +vt 0.701503 0.767118 +vt 0.651218 0.816520 +vt 0.556729 0.720353 +vt 0.563894 0.620733 +vt 0.506596 0.676492 +vt 0.504606 0.678666 +vt 0.561357 0.622350 +vt 0.357521 0.145897 +vt 0.464422 0.288567 +vt 0.487473 0.261159 +vt 0.464422 0.288567 +vt 0.357521 0.145897 +vt 0.296184 0.151459 +vt 0.928266 0.260636 +vt 0.952737 0.150680 +vt 0.926583 0.149422 +vt 0.954807 0.287985 +vt 0.487473 0.261159 +vt 0.954807 0.287985 +vt 0.928266 0.260636 +vt 0.464422 0.288567 +vt 0.453053 0.288049 +vt 0.296184 0.151459 +vt 0.284111 0.152277 +vt 0.296184 0.151459 +vt 0.453053 0.288049 +vt 0.464422 0.288567 +vt 0.926583 0.149422 +vt 0.357521 0.145897 +vt 0.928266 0.260636 +vt 0.487473 0.261159 +vt 0.642208 0.530008 +vt 0.598002 0.549292 +vt 0.611213 0.517318 +vt 0.628996 0.561982 +vt 0.735118 0.642581 +vt 0.645826 0.531772 +vt 0.774475 0.549811 +vt 0.632677 0.562768 +vt 0.733689 0.642190 +vt 0.641904 0.532149 +vt 0.771938 0.551867 +vt 0.629125 0.562327 +vt 0.773312 0.549431 +vt 0.631576 0.562175 +vt 0.733919 0.642186 +vt 0.644738 0.531184 +vt 0.733634 0.640719 +vt 0.641849 0.530678 +vt 0.771883 0.550396 +vt 0.629070 0.560856 +vt 0.802708 0.662256 +vt 0.804521 0.661447 +vt 0.834417 0.584385 +vt 0.804466 0.659976 +vt 0.802708 0.662256 +vt 0.894434 0.701168 +vt 0.775667 0.724124 +vt 0.867392 0.763037 +vt 0.774455 0.723697 +vt 0.866164 0.762648 +vt 0.801384 0.662163 +vt 0.893093 0.701113 +vt 0.861268 0.522348 +vt 0.952994 0.561261 +vt 0.835711 0.584464 +vt 0.927436 0.623377 +vt 0.834417 0.584385 +vt 0.926126 0.623335 +vt 0.860137 0.521956 +vt 0.951846 0.560906 +vt 0.946451 0.728491 +vt 0.927436 0.623377 +vt 0.983109 0.642083 +vt 0.945771 0.728335 +vt 0.927034 0.628700 +vt 0.981397 0.644206 +vt 0.981915 0.641773 +vt 0.893093 0.701113 +vt 0.945223 0.728167 +vt 0.945715 0.726865 +vt 0.926978 0.627229 +vt 0.981341 0.642736 +vt 0.835711 0.584464 +vt 0.834909 0.589688 +vt 0.801384 0.662163 +vt 0.834854 0.588217 +vt 0.894434 0.701168 +vt 0.896646 0.700459 +vt 0.926126 0.623335 +vt 0.896591 0.698988 +vt 0.774475 0.549811 +vt 0.735118 0.642581 +vt 0.773312 0.549431 +vt 0.733919 0.642186 +vt 0.983109 0.642083 +vt 0.946451 0.728491 +vt 0.981915 0.641773 +vt 0.945223 0.728167 +vt 0.035491 0.007166 +vt 0.025120 0.042034 +vt 0.012310 0.028503 +vt 0.048302 0.020698 +vt 0.011935 0.028441 +vt 0.048410 0.020382 +vt 0.035503 0.007264 +vt 0.025158 0.042143 +vt 0.034402 0.008856 +vt 0.025297 0.042722 +vt 0.012614 0.029981 +vt 0.047085 0.021597 +vt 0.034122 0.009316 +vt 0.025811 0.042994 +vt 0.013098 0.030169 +vt 0.046835 0.022141 +vt 0.025158 0.042143 +vt 0.065625 0.022318 +vt 0.048410 0.020382 +vt 0.023979 0.061449 +vt 0.048302 0.020698 +vt 0.023332 0.061083 +vt 0.025120 0.042034 +vt 0.065577 0.022200 +vt 0.046835 0.022141 +vt 0.025455 0.059905 +vt 0.025811 0.042994 +vt 0.063768 0.021904 +vt 0.047085 0.021597 +vt 0.023936 0.061066 +vt 0.025297 0.042722 +vt 0.063642 0.022568 +vt 0.210956 0.152364 +vt 0.453053 0.288049 +vt 0.284111 0.152277 +vt 0.379898 0.288135 +vt 0.132117 0.022442 +vt 0.209128 0.135294 +vt 0.071801 0.023357 +vt 0.269444 0.134379 +vt 0.745407 0.896583 +vt 0.549748 0.641825 +vt 0.771751 0.870306 +vt 0.549748 0.641825 +vt 0.745407 0.896583 +vt 0.523404 0.668103 +vt 0.041541 0.064563 +vt 0.110865 0.151096 +vt 0.110099 0.133097 +vt 0.023016 0.063279 +vt 0.065675 0.039862 +vt 0.023016 0.063279 +vt 0.041541 0.064563 +vt 0.063272 0.022717 +vt 0.209128 0.135294 +vt 0.063220 0.022601 +vt 0.108250 0.147543 +vt 0.022357 0.062935 +vt 0.952737 0.150680 +vt 0.989982 0.287944 +vt 0.988528 0.150637 +vt 0.954807 0.287985 +vt 0.712307 0.014683 +vt 0.683074 0.130257 +vt 0.682797 0.015131 +vt 0.712072 0.129816 +vt 0.447563 0.912220 +vt 0.646190 0.810714 +vt 0.493544 0.959395 +vt 0.600209 0.763539 +vt 0.553707 0.594408 +vt 0.594216 0.555842 +vt 0.063768 0.021904 +vt 0.538047 0.577009 +vt 0.025455 0.059905 +vt 0.591842 0.554624 +vt 0.063642 0.022568 +vt 0.550764 0.590300 +vt 0.023936 0.061066 +vt 0.575025 0.536287 +vt 0.540759 0.506256 +vt 0.605865 0.643604 +vt 0.504416 0.543946 +vt 0.641994 0.605704 +vt 0.028768 0.315878 +vt 0.202071 0.336757 +vt 0.027449 0.336516 +vt 0.249474 0.315834 +vt 0.553561 0.459581 +vt 0.987980 0.445430 +vt 0.972465 0.459546 +vt 0.573256 0.445350 +vt 0.970799 0.356369 +vt 0.573258 0.370185 +vt 0.553497 0.356383 +vt 0.986636 0.370386 +vt 0.970984 0.316621 +vt 0.986932 0.304422 +vt 0.987672 0.509975 +vt 0.972581 0.497394 +vt 0.569009 0.608243 +vt 0.605815 0.567217 +vt 0.519492 0.356419 +vt 0.518952 0.460602 +vt 0.553930 0.496673 +vt 0.566306 0.510951 +vt 0.570654 0.299299 +vt 0.553420 0.311936 +vt 0.493513 0.593817 +vt 0.359458 0.797109 +vt 0.496085 0.659837 +vt 0.359458 0.797109 +vt 0.493513 0.593817 +vt 0.322055 0.760188 +vt 0.663829 0.821617 +vt 0.504844 0.568774 +vt 0.752741 0.817728 +vt 0.504844 0.568774 +vt 0.663829 0.821617 +vt 0.458191 0.615277 +vt 0.566935 0.630141 +vt 0.741992 0.902941 +vt 0.517733 0.676750 +vt 0.791194 0.856332 +vt 0.554153 0.460522 +vt 0.591842 0.554624 +vt 0.610443 0.650049 +vt 0.569009 0.608243 +vt 0.462484 0.526262 +vt 0.504844 0.568774 +vt 0.458191 0.615277 +vt 0.732122 0.694266 +vt 0.457561 0.619544 +vt 0.390949 0.451227 +vt 0.340691 0.500669 +vt 0.591842 0.554624 +vt 0.794376 0.835595 +vt 0.610443 0.650049 +vt 0.320432 0.667837 +vt 0.458191 0.615277 +vt 0.362798 0.710345 +vt 0.458191 0.615277 +vt 0.320432 0.667837 +vt 0.462484 0.526262 +vt 0.497830 0.296368 +vt 0.427675 0.367237 +vt 0.428364 0.295478 +vt 0.497141 0.368128 +vt 0.505434 0.370200 +vt 0.505331 0.448202 +vt 0.340703 0.500655 +vt 0.457472 0.619530 +vt 0.390797 0.451331 +vt 0.500490 0.663115 +vt 0.390966 0.451281 +vt 0.340681 0.500683 +vt 0.496085 0.659837 +vt 0.496085 0.659837 +vt 0.697157 0.799236 +vt 0.493513 0.593817 +vt 0.568435 0.916685 +vt 0.752741 0.817728 +vt 0.610801 0.959193 +vt 0.752741 0.817728 +vt 0.568435 0.916685 +vt 0.663829 0.821617 +vt 0.497249 0.296187 +vt 0.427093 0.367056 +vt 0.427782 0.295297 +vt 0.496560 0.367946 +vt 0.556729 0.720353 +vt 0.343496 0.817418 +vt 0.500490 0.663115 +vt 0.400064 0.874333 +vt 0.522617 0.686211 +vt 0.772105 0.841392 +vt 0.722776 0.889872 +vt 0.571945 0.637731 +vt 0.029620 0.984657 +vt 0.208507 0.969157 +vt 0.252569 0.985593 +vt 0.029389 0.967030 +vt 0.028206 0.385955 +vt 0.204105 0.386185 +vt 0.253155 0.395067 +vt 0.025887 0.459502 +vt 0.188981 0.459844 +vt 0.027722 0.854258 +vt 0.190816 0.854600 +vt 0.029328 0.920986 +vt 0.210660 0.923674 +vt 0.242699 0.460218 +vt 0.245338 0.854227 +vt 0.252309 0.930891 +vt 0.028451 0.921573 +vt 0.252391 0.932079 +vt 0.598787 0.669597 +vt 0.703379 0.867938 +vt 0.552840 0.714749 +vt 0.752285 0.821907 +vt 0.736422 0.012871 +vt 0.916139 0.130638 +vt 0.737358 0.131432 +vt 0.916139 0.012871 +vt 0.598503 0.669876 +vt 0.702368 0.868932 +vt 0.552077 0.715498 +vt 0.751274 0.822901 +vt 0.319760 0.835283 +vt 0.300147 0.911197 +vt 0.317475 0.479551 +vt 0.294135 0.406099 +vt 0.674120 0.126945 +vt 0.673842 0.014528 +vt 0.132117 0.022442 +vt 0.132117 0.022442 +vt 0.269444 0.134379 +vt 0.674120 0.126945 +vt 0.201464 0.137566 +vt 0.683074 0.130257 +vt 0.269444 0.134379 +vt 0.674120 0.126945 +vt 0.269444 0.134379 +vt 0.683074 0.130257 +vt 0.683074 0.130257 +vt 0.682797 0.015131 +vt 0.674120 0.126945 +vt 0.673842 0.014528 +vt 0.674120 0.126945 +vt 0.682797 0.015131 +vt 0.647034 0.813468 +vt 0.597499 0.763578 +vt 0.448555 0.914611 +vt 0.492025 0.958847 +vt 0.640803 0.812643 +vt 0.597333 0.768407 +vt 0.647261 0.815930 +vt 0.598243 0.765532 +vt 0.450490 0.915256 +vt 0.493574 0.959098 +vt 0.641027 0.814195 +vt 0.597944 0.770354 +vt 0.597499 0.763578 +vt 0.647034 0.813468 +vt 0.747627 0.909508 +vt 0.747627 0.909508 +vt 0.509004 0.668989 +vt 0.597499 0.763578 +vt 0.598243 0.765532 +vt 0.647261 0.815930 +vt 0.740284 0.906069 +vt 0.740284 0.906069 +vt 0.503965 0.663285 +vt 0.598243 0.765532 +vt 0.537299 0.923005 +vt 0.483584 0.868868 +vt 0.592736 0.752811 +vt 0.654247 0.814805 +vt 0.483852 0.865836 +vt 0.537044 0.920488 +vt 0.647222 0.820979 +vt 0.586311 0.758396 +vt 0.747627 0.909508 +vt 0.796653 0.863183 +vt 0.558029 0.622664 +vt 0.509004 0.668989 +vt 0.539725 0.992216 +vt 0.505456 0.956870 +vt 0.648299 0.813382 +vt 0.682568 0.847951 +vt 0.551186 0.615030 +vt 0.503965 0.663285 +vt 0.740284 0.906069 +vt 0.787505 0.857813 +vt 0.952233 0.985260 +vt 0.984205 0.954259 +vt 0.851318 0.814006 +vt 0.811612 0.852504 +vt 0.870723 0.945112 +vt 0.825025 0.990459 +vt 0.646616 0.821792 +vt 0.646616 0.821792 +vt 0.672612 0.734479 +vt 0.870723 0.945112 +vt 0.829209 0.987755 +vt 0.869365 0.948108 +vt 0.705926 0.772152 +vt 0.655721 0.820941 +vt 0.955599 0.990783 +vt 0.986451 0.960183 +vt 0.853394 0.818481 +vt 0.853394 0.818481 +vt 0.835786 0.877370 +vt 0.955599 0.990783 +vt 0.869526 0.947996 +vt 0.829184 0.987657 +vt 0.655999 0.821124 +vt 0.706294 0.772244 +vt 0.823909 0.991444 +vt 0.870047 0.946545 +vt 0.674064 0.733928 +vt 0.674064 0.733928 +vt 0.647222 0.820979 +vt 0.823909 0.991444 +vt 0.828978 0.987744 +vt 0.869469 0.947964 +vt 0.701503 0.767118 +vt 0.651218 0.816520 +vt 0.807277 0.916486 +vt 0.781732 0.941795 +vt 0.682568 0.847951 +vt 0.682568 0.847951 +vt 0.697157 0.799236 +vt 0.807277 0.916486 +vt 0.672612 0.734479 +vt 0.646616 0.821792 +vt 0.585106 0.759798 +vt 0.853394 0.818481 +vt 0.794376 0.835595 +vt 0.835786 0.877370 +vt 0.674064 0.733928 +vt 0.586311 0.758396 +vt 0.647222 0.820979 +vt 0.697157 0.799236 +vt 0.682568 0.847951 +vt 0.648299 0.813382 +vt 0.811612 0.852504 +vt 0.851318 0.814006 +vt 0.776596 0.738943 +vt 0.647622 0.712276 +vt 0.521957 0.684769 +vt 0.597460 0.761549 +vt 0.647484 0.712183 +vt 0.597115 0.761577 +vt 0.521525 0.684603 +vt 0.701503 0.767118 +vt 0.556729 0.720353 +vt 0.651218 0.816520 +vt 0.563894 0.620733 +vt 0.506596 0.676492 +vt 0.504606 0.678666 +vt 0.561357 0.622350 +vt 0.357521 0.145897 +vt 0.487473 0.261159 +vt 0.464422 0.288567 +vt 0.464422 0.288567 +vt 0.296184 0.151459 +vt 0.357521 0.145897 +vt 0.928266 0.260636 +vt 0.926583 0.149422 +vt 0.952737 0.150680 +vt 0.954807 0.287985 +vt 0.487473 0.261159 +vt 0.928266 0.260636 +vt 0.954807 0.287985 +vt 0.464422 0.288567 +vt 0.453053 0.288049 +vt 0.284111 0.152277 +vt 0.296184 0.151459 +vt 0.296184 0.151459 +vt 0.464422 0.288567 +vt 0.453053 0.288049 +vt 0.926583 0.149422 +vt 0.928266 0.260636 +vt 0.357521 0.145897 +vt 0.487473 0.261159 +vt 0.642208 0.530008 +vt 0.611213 0.517318 +vt 0.598002 0.549292 +vt 0.628996 0.561982 +vt 0.735118 0.642581 +vt 0.774475 0.549811 +vt 0.645826 0.531772 +vt 0.632677 0.562768 +vt 0.733689 0.642190 +vt 0.771938 0.551867 +vt 0.641904 0.532149 +vt 0.629125 0.562327 +vt 0.773312 0.549431 +vt 0.733919 0.642186 +vt 0.631576 0.562175 +vt 0.644738 0.531184 +vt 0.733634 0.640719 +vt 0.771883 0.550396 +vt 0.641849 0.530678 +vt 0.629070 0.560856 +vt 0.802708 0.662256 +vt 0.804521 0.661447 +vt 0.834417 0.584385 +vt 0.804466 0.659976 +vt 0.802708 0.662256 +vt 0.775667 0.724124 +vt 0.894434 0.701168 +vt 0.867392 0.763037 +vt 0.774455 0.723697 +vt 0.801384 0.662163 +vt 0.866164 0.762648 +vt 0.893093 0.701113 +vt 0.861268 0.522348 +vt 0.835711 0.584464 +vt 0.952994 0.561261 +vt 0.927436 0.623377 +vt 0.834417 0.584385 +vt 0.860137 0.521956 +vt 0.926126 0.623335 +vt 0.951846 0.560906 +vt 0.946451 0.728491 +vt 0.983109 0.642083 +vt 0.927436 0.623377 +vt 0.945771 0.728335 +vt 0.981397 0.644206 +vt 0.927034 0.628700 +vt 0.981915 0.641773 +vt 0.945223 0.728167 +vt 0.893093 0.701113 +vt 0.945715 0.726865 +vt 0.981341 0.642736 +vt 0.926978 0.627229 +vt 0.835711 0.584464 +vt 0.834909 0.589688 +vt 0.801384 0.662163 +vt 0.834854 0.588217 +vt 0.894434 0.701168 +vt 0.896646 0.700459 +vt 0.926126 0.623335 +vt 0.896591 0.698988 +vt 0.774475 0.549811 +vt 0.735118 0.642581 +vt 0.773312 0.549431 +vt 0.733919 0.642186 +vt 0.983109 0.642083 +vt 0.946451 0.728491 +vt 0.981915 0.641773 +vt 0.945223 0.728167 +vt 0.035491 0.007166 +vt 0.012310 0.028503 +vt 0.025120 0.042034 +vt 0.048302 0.020698 +vt 0.011935 0.028441 +vt 0.035503 0.007264 +vt 0.048410 0.020382 +vt 0.025158 0.042143 +vt 0.034402 0.008856 +vt 0.012614 0.029981 +vt 0.025297 0.042722 +vt 0.047085 0.021597 +vt 0.034122 0.009316 +vt 0.013098 0.030169 +vt 0.025811 0.042994 +vt 0.046835 0.022141 +vt 0.025158 0.042143 +vt 0.048410 0.020382 +vt 0.065625 0.022318 +vt 0.023979 0.061449 +vt 0.048302 0.020698 +vt 0.025120 0.042034 +vt 0.023332 0.061083 +vt 0.065577 0.022200 +vt 0.046835 0.022141 +vt 0.025811 0.042994 +vt 0.025455 0.059905 +vt 0.063768 0.021904 +vt 0.047085 0.021597 +vt 0.025297 0.042722 +vt 0.023936 0.061066 +vt 0.063642 0.022568 +vt 0.210956 0.152364 +vt 0.284111 0.152277 +vt 0.453053 0.288049 +vt 0.379898 0.288135 +vt 0.132117 0.022442 +vt 0.071801 0.023357 +vt 0.209128 0.135294 +vt 0.269444 0.134379 +vt 0.745407 0.896583 +vt 0.771751 0.870306 +vt 0.549748 0.641825 +vt 0.549748 0.641825 +vt 0.523404 0.668103 +vt 0.745407 0.896583 +vt 0.041541 0.064563 +vt 0.110099 0.133097 +vt 0.110865 0.151096 +vt 0.023016 0.063279 +vt 0.065675 0.039862 +vt 0.041541 0.064563 +vt 0.023016 0.063279 +vt 0.063272 0.022717 +vt 0.209128 0.135294 +vt 0.063220 0.022601 +vt 0.022357 0.062935 +vt 0.108250 0.147543 +vt 0.952737 0.150680 +vt 0.988528 0.150637 +vt 0.989982 0.287944 +vt 0.954807 0.287985 +vt 0.712307 0.014683 +vt 0.682797 0.015131 +vt 0.683074 0.130257 +vt 0.712072 0.129816 +vt 0.447563 0.912220 +vt 0.493544 0.959395 +vt 0.646190 0.810714 +vt 0.600209 0.763539 +vt 0.553707 0.594408 +vt 0.594216 0.555842 +vt 0.063768 0.021904 +vt 0.025455 0.059905 +vt 0.538047 0.577009 +vt 0.591842 0.554624 +vt 0.063642 0.022568 +vt 0.023936 0.061066 +vt 0.550764 0.590300 +vt 0.575025 0.536287 +vt 0.540759 0.506256 +vt 0.504416 0.543946 +vt 0.605865 0.643604 +vt 0.641994 0.605704 +vt 0.202071 0.336757 +vt 0.249474 0.315834 +vt 0.553561 0.459581 +vt 0.972465 0.459546 +vt 0.987980 0.445430 +vt 0.573256 0.445350 +vt 0.970799 0.356369 +vt 0.553497 0.356383 +vt 0.573258 0.370185 +vt 0.986636 0.370386 +vt 0.970984 0.316621 +vt 0.986932 0.304422 +vt 0.972581 0.497394 +vt 0.987672 0.509975 +vt 0.569009 0.608243 +vt 0.605815 0.567217 +vt 0.519492 0.356419 +vt 0.518952 0.460602 +vt 0.553930 0.496673 +vt 0.566306 0.510951 +vt 0.570654 0.299299 +vt 0.553420 0.311936 +vt 0.493513 0.593817 +vt 0.496085 0.659837 +vt 0.359458 0.797109 +vt 0.359458 0.797109 +vt 0.322055 0.760188 +vt 0.493513 0.593817 +vt 0.663829 0.821617 +vt 0.752741 0.817728 +vt 0.504844 0.568774 +vt 0.504844 0.568774 +vt 0.458191 0.615277 +vt 0.663829 0.821617 +vt 0.566935 0.630141 +vt 0.517733 0.676750 +vt 0.741992 0.902941 +vt 0.791194 0.856332 +vt 0.554153 0.460522 +vt 0.591842 0.554624 +vt 0.569009 0.608243 +vt 0.610443 0.650049 +vt 0.462484 0.526262 +vt 0.458191 0.615277 +vt 0.504844 0.568774 +vt 0.732122 0.694266 +vt 0.457561 0.619544 +vt 0.390949 0.451227 +vt 0.340691 0.500669 +vt 0.591842 0.554624 +vt 0.610443 0.650049 +vt 0.794376 0.835595 +vt 0.320432 0.667837 +vt 0.362798 0.710345 +vt 0.458191 0.615277 +vt 0.458191 0.615277 +vt 0.462484 0.526262 +vt 0.320432 0.667837 +vt 0.497830 0.296368 +vt 0.428364 0.295478 +vt 0.427675 0.367237 +vt 0.497141 0.368128 +vt 0.505434 0.370200 +vt 0.505331 0.448202 +vt 0.457472 0.619530 +vt 0.340703 0.500655 +vt 0.390797 0.451331 +vt 0.500490 0.663115 +vt 0.390966 0.451281 +vt 0.340681 0.500683 +vt 0.496085 0.659837 +vt 0.496085 0.659837 +vt 0.493513 0.593817 +vt 0.697157 0.799236 +vt 0.568435 0.916685 +vt 0.610801 0.959193 +vt 0.752741 0.817728 +vt 0.752741 0.817728 +vt 0.663829 0.821617 +vt 0.568435 0.916685 +vt 0.497249 0.296187 +vt 0.427782 0.295297 +vt 0.427093 0.367056 +vt 0.496560 0.367946 +vt 0.556729 0.720353 +vt 0.500490 0.663115 +vt 0.343496 0.817418 +vt 0.400064 0.874333 +vt 0.522617 0.686211 +vt 0.722776 0.889872 +vt 0.772105 0.841392 +vt 0.571945 0.637731 +vt 0.252569 0.985593 +vt 0.208507 0.969157 +vt 0.204105 0.386185 +vt 0.253155 0.395067 +vt 0.188981 0.459844 +vt 0.190816 0.854600 +vt 0.210660 0.923674 +vt 0.242699 0.460218 +vt 0.245338 0.854227 +vt 0.252309 0.930891 +vt 0.252391 0.932079 +vt 0.703379 0.867938 +vt 0.752285 0.821907 +vt 0.737358 0.131432 +vt 0.916139 0.130638 +vt 0.702368 0.868932 +vt 0.751274 0.822901 +vt 0.319760 0.835283 +vt 0.300147 0.911197 +vt 0.317475 0.479551 +vt 0.294135 0.406099 +vn -0.999745 -0.022571 -0.000427 +vn -0.999745 -0.022571 -0.000427 +vn -0.999745 -0.022571 -0.000427 +vn -0.999971 0.005425 0.005345 +vn -0.999971 0.005425 0.005345 +vn -0.999971 0.005425 0.005345 +vn -0.148086 -0.988975 0.000000 +vn -0.148086 -0.988975 0.000000 +vn -0.148086 -0.988975 0.000000 +vn -0.464450 -0.885579 0.005999 +vn -0.464450 -0.885579 0.005999 +vn -0.464450 -0.885579 0.005999 +vn -0.847890 -0.018688 0.529842 +vn -0.847890 -0.018688 0.529842 +vn -0.847890 -0.018688 0.529842 +vn -0.845153 -0.019081 0.534183 +vn -0.845153 -0.019081 0.534183 +vn -0.845153 -0.019081 0.534183 +vn 0.000000 -0.000001 -1.000000 +vn 0.000000 0.000001 -1.000000 +vn 0.000000 -0.000001 -1.000000 +vn 0.000000 0.000001 -1.000000 +vn -0.999992 0.004070 0.000000 +vn -0.999992 0.004070 0.000000 +vn -0.999992 0.004070 0.000000 +vn -0.999992 0.004070 0.000000 +vn -0.000000 0.000000 1.000000 +vn -0.000000 -0.000000 1.000000 +vn 0.000000 0.000000 1.000000 +vn -0.000000 -0.000000 1.000000 +vn 0.999992 -0.004076 -0.000000 +vn 0.999992 -0.004076 -0.000000 +vn 0.999992 -0.004076 0.000000 +vn 0.999992 -0.004076 -0.000000 +vn -0.004429 -0.913622 -0.406539 +vn -0.004429 -0.913622 -0.406539 +vn -0.004429 -0.913622 -0.406539 +vn -0.004027 -0.907532 -0.419964 +vn -0.004027 -0.907532 -0.419964 +vn -0.004027 -0.907532 -0.419964 +vn -0.004381 -0.903704 0.428136 +vn -0.004381 -0.903704 0.428136 +vn -0.004381 -0.903704 0.428136 +vn -0.004036 -0.909589 0.415489 +vn -0.004036 -0.909589 0.415489 +vn -0.004036 -0.909589 0.415489 +vn -0.020304 -0.999794 -0.000000 +vn -0.020304 -0.999794 -0.000000 +vn -0.020305 -0.999794 -0.000000 +vn -0.020304 -0.999794 -0.000000 +vn 0.012824 -0.999918 -0.000000 +vn 0.012824 -0.999918 -0.000000 +vn 0.012824 -0.999918 -0.000000 +vn 0.012824 -0.999918 -0.000000 +vn -0.000000 -0.000001 -1.000000 +vn -0.000000 -0.000001 -1.000000 +vn -0.000000 -0.000001 -1.000000 +vn -0.000000 -0.000001 -1.000000 +vn 0.004437 0.999990 -0.000000 +vn 0.004437 0.999990 -0.000000 +vn 0.004437 0.999990 0.000000 +vn 0.004437 0.999990 -0.000000 +vn -0.000000 -0.000001 1.000000 +vn -0.000000 -0.000001 1.000000 +vn -0.000000 -0.000001 1.000000 +vn -0.000000 -0.000001 1.000000 +vn -0.999469 -0.018316 -0.026931 +vn -0.999469 -0.018316 -0.026931 +vn -0.999469 -0.018316 -0.026931 +vn -0.999469 -0.018316 -0.026931 +vn 0.021530 -0.999231 -0.032765 +vn 0.021530 -0.999231 -0.032765 +vn 0.021530 -0.999231 -0.032765 +vn 0.006116 -0.999583 -0.028232 +vn 0.006116 -0.999583 -0.028232 +vn 0.006116 -0.999583 -0.028232 +vn 0.999329 0.018313 -0.031720 +vn 0.999329 0.018313 -0.031720 +vn 0.999329 0.018313 -0.031720 +vn 0.999329 0.018313 -0.031720 +vn -0.021533 0.999381 -0.027818 +vn -0.021533 0.999381 -0.027818 +vn -0.021533 0.999381 -0.027818 +vn -0.039109 0.998716 -0.032200 +vn -0.039109 0.998716 -0.032200 +vn -0.039109 0.998716 -0.032200 +vn -0.999329 -0.018313 -0.031720 +vn -0.999329 -0.018313 -0.031720 +vn -0.999329 -0.018313 -0.031720 +vn -0.999329 -0.018313 -0.031720 +vn 0.021533 -0.999381 -0.027818 +vn 0.021533 -0.999381 -0.027818 +vn 0.021533 -0.999381 -0.027818 +vn 0.039108 -0.998716 -0.032200 +vn 0.039108 -0.998716 -0.032200 +vn 0.039108 -0.998716 -0.032200 +vn 0.999469 0.018316 -0.026931 +vn 0.999469 0.018316 -0.026931 +vn 0.999469 0.018316 -0.026931 +vn 0.999469 0.018316 -0.026931 +vn -0.021530 0.999231 -0.032765 +vn -0.021530 0.999231 -0.032765 +vn -0.021530 0.999231 -0.032765 +vn -0.006116 0.999583 -0.028232 +vn -0.006116 0.999583 -0.028232 +vn -0.006116 0.999583 -0.028232 +vn 0.021541 -0.999768 -0.000000 +vn 0.021541 -0.999768 0.000000 +vn 0.021541 -0.999768 -0.000000 +vn -0.021714 0.999764 0.000317 +vn -0.021541 0.999768 0.000000 +vn -0.021714 0.999764 0.000317 +vn 0.021542 -0.999768 -0.000000 +vn 0.021542 -0.999768 -0.000000 +vn 0.021541 -0.999768 0.000000 +vn -0.021910 0.999760 -0.000674 +vn -0.021910 0.999760 -0.000674 +vn -0.021542 0.999768 -0.000000 +vn -0.999832 -0.018323 -0.000000 +vn -0.999832 -0.018323 -0.000000 +vn -0.999832 -0.018323 -0.000000 +vn 0.999832 0.018322 0.000000 +vn 0.999832 0.018322 -0.000000 +vn 0.999832 0.018322 0.000000 +vn -0.999832 -0.018322 -0.000000 +vn -0.999832 -0.018322 -0.000000 +vn -0.999832 -0.018322 0.000000 +vn 0.999832 0.018322 0.000000 +vn 0.999832 0.018322 0.000000 +vn 0.999832 0.018322 0.000000 +vn 0.021541 -0.999768 0.000000 +vn 0.021541 -0.999768 0.000000 +vn 0.021541 -0.999768 -0.000000 +vn 0.021541 -0.999768 -0.000000 +vn 0.968686 0.195526 0.153029 +vn 0.968686 0.195526 0.153029 +vn 0.968686 0.195526 0.153029 +vn 0.973794 0.182611 0.135571 +vn 0.973794 0.182611 0.135571 +vn 0.973794 0.182611 0.135571 +vn 0.956360 0.020938 -0.291439 +vn 0.956360 0.020938 -0.291439 +vn 0.956184 0.021083 -0.292008 +vn 0.956360 0.020938 -0.291439 +vn 0.947601 0.319455 -0.000000 +vn 0.947601 0.319455 -0.000000 +vn 0.947601 0.319455 -0.000000 +vn 0.947601 0.319455 -0.000000 +vn 0.501241 0.666644 0.551674 +vn 0.501241 0.666644 0.551674 +vn 0.501241 0.666644 0.551674 +vn 0.508597 0.663687 0.548496 +vn 0.508597 0.663687 0.548496 +vn 0.508597 0.663687 0.548496 +vn 0.999757 0.022044 0.000000 +vn 0.999757 0.022044 0.000000 +vn 0.999757 0.022044 0.000000 +vn 0.999757 0.022044 0.000000 +vn 0.000000 0.000000 1.000000 +vn 0.000000 0.000000 1.000000 +vn 0.000000 0.000000 1.000000 +vn 0.000000 0.000000 1.000000 +vn 0.921437 0.016886 0.388160 +vn 0.967760 0.017734 0.251249 +vn 0.854236 0.015654 0.519649 +vn 0.967760 0.017734 0.251250 +vn 0.019763 -0.917212 0.397908 +vn 0.020806 -0.965657 0.258986 +vn 0.018253 -0.847154 0.531034 +vn 0.020806 -0.965657 0.258986 +vn -0.921438 -0.016886 0.388159 +vn -0.967760 -0.017734 0.251249 +vn -0.854236 -0.015654 0.519649 +vn -0.967760 -0.017734 0.251249 +vn -0.019762 0.917212 0.397908 +vn -0.020806 0.965657 0.258986 +vn -0.018253 0.847154 0.531034 +vn -0.020806 0.965657 0.258986 +vn 0.893681 0.016377 0.448404 +vn 0.019147 -0.888655 0.458176 +vn -0.893681 -0.016377 0.448404 +vn -0.019147 0.888655 0.458176 +vn 0.701700 -0.674268 0.230173 +vn 0.707594 -0.679932 -0.192362 +vn 0.712574 -0.684717 0.152974 +vn 0.690072 -0.663095 -0.290011 +vn -0.674165 -0.701592 0.230802 +vn -0.679869 -0.707528 -0.192829 +vn -0.684673 -0.712527 0.153389 +vn -0.662945 -0.689916 -0.290723 +vn 0.674165 0.701592 0.230802 +vn 0.679869 0.707528 -0.192829 +vn 0.684673 0.712527 0.153389 +vn 0.662945 0.689916 -0.290723 +vn -0.701700 0.674268 0.230174 +vn -0.707594 0.679932 -0.192362 +vn -0.712573 0.684717 0.152974 +vn -0.690071 0.663095 -0.290012 +vn 0.698442 0.012799 -0.715552 +vn 0.858479 0.015732 -0.512607 +vn 0.698442 0.012799 -0.715552 +vn 0.014796 -0.686712 -0.726779 +vn 0.018371 -0.852614 -0.522218 +vn 0.014796 -0.686712 -0.726779 +vn -0.698441 -0.012799 -0.715553 +vn -0.858479 -0.015732 -0.512607 +vn -0.698441 -0.012799 -0.715553 +vn -0.014796 0.686711 -0.726780 +vn -0.018371 0.852614 -0.522219 +vn -0.014796 0.686711 -0.726780 +vn 0.974379 0.017856 0.224202 +vn 0.020969 -0.973180 0.229088 +vn -0.974379 -0.017856 0.224202 +vn -0.020969 0.973180 0.229088 +vn 0.966434 0.017710 -0.256303 +vn 0.020794 -0.965085 -0.261109 +vn -0.966434 -0.017711 -0.256304 +vn -0.020794 0.965085 -0.261110 +vn 0.619054 0.644239 0.449141 +vn 0.644657 -0.619456 0.447987 +vn -0.644657 0.619456 0.447987 +vn -0.619055 -0.644239 0.449140 +vn 0.575750 0.599173 -0.556331 +vn 0.599769 -0.576323 -0.555094 +vn -0.599768 0.576322 -0.555095 +vn -0.575749 -0.599172 -0.556332 +vn 0.999832 0.018322 -0.000000 +vn 0.999832 0.018322 -0.000000 +vn 0.999832 0.018322 -0.000000 +vn 0.999832 0.018322 -0.000000 +vn 0.021541 -0.999768 0.000000 +vn 0.021541 -0.999768 0.000000 +vn 0.021541 -0.999768 0.000000 +vn 0.021541 -0.999768 0.000000 +vn -0.999832 -0.018322 0.000000 +vn -0.999832 -0.018322 0.000000 +vn -0.999832 -0.018322 0.000000 +vn -0.999832 -0.018322 0.000000 +vn -0.021541 0.999768 -0.000000 +vn -0.021541 0.999768 -0.000000 +vn -0.021541 0.999768 -0.000000 +vn -0.021541 0.999768 -0.000000 +vn 0.014158 -0.657083 0.753685 +vn 0.014158 -0.657083 0.753685 +vn 0.014158 -0.657083 0.753685 +vn 0.014158 -0.657083 0.753685 +vn 0.669174 0.012263 0.743005 +vn 0.669174 0.012263 0.743005 +vn 0.669174 0.012263 0.743005 +vn 0.669174 0.012263 0.743005 +vn -0.014158 0.657082 0.753686 +vn -0.014158 0.657082 0.753686 +vn -0.014158 0.657082 0.753686 +vn -0.014158 0.657082 0.753686 +vn -0.669173 -0.012263 0.743005 +vn -0.669173 -0.012263 0.743005 +vn -0.669173 -0.012263 0.743005 +vn -0.669173 -0.012263 0.743005 +vn 0.999999 0.001050 0.000000 +vn 0.999999 0.001050 0.000000 +vn 0.999999 0.001050 0.000000 +vn 0.999999 0.001050 0.000000 +vn -0.999999 -0.001055 0.000000 +vn -0.999999 -0.001055 0.000000 +vn -0.999999 -0.001055 0.000000 +vn -0.999999 -0.001055 0.000000 +vn 0.000000 0.770164 0.637845 +vn 0.000000 0.770164 0.637845 +vn 0.000000 0.770164 0.637845 +vn -0.016618 0.771290 0.636266 +vn -0.016618 0.771290 0.636266 +vn -0.016618 0.771290 0.636266 +vn 0.193431 -0.981114 0.000000 +vn 0.193431 -0.981114 0.000000 +vn 0.193431 -0.981114 0.000000 +vn 0.193431 -0.981114 0.000000 +vn 0.021301 -0.988620 0.148918 +vn 0.021301 -0.988620 0.148918 +vn 0.021301 -0.988620 0.148919 +vn 0.021301 -0.988620 0.148918 +vn -0.148086 -0.988975 0.000000 +vn 0.999832 0.018322 0.000000 +vn 0.999832 0.018322 0.000000 +vn 0.999832 0.018322 -0.000000 +vn 0.999760 0.021888 -0.000000 +vn 0.999760 0.021888 -0.000000 +vn 0.999760 0.021888 -0.000000 +vn 0.999760 0.021888 -0.000000 +vn -0.999757 -0.022035 0.000000 +vn -0.999757 -0.022035 0.000000 +vn -0.999757 -0.022035 0.000000 +vn -0.999757 -0.022035 0.000000 +vn -0.000211 0.004415 -0.999990 +vn -0.000211 0.004415 -0.999990 +vn 0.000000 0.004485 -0.999990 +vn -0.000211 0.004415 -0.999990 +vn 0.999832 0.018322 0.000000 +vn 0.999832 0.018322 0.000000 +vn -0.021542 0.999768 -0.000000 +vn -0.021542 0.999768 -0.000000 +vn -0.021542 0.999768 -0.000000 +vn -0.021714 0.999764 0.000317 +vn -0.999832 -0.018323 -0.000000 +vn -0.999832 -0.018320 -0.000006 +vn -0.999832 -0.018323 -0.000000 +vn -0.999832 -0.018322 0.000000 +vn -0.999999 -0.001611 0.000000 +vn -0.999999 -0.001611 0.000000 +vn -0.999999 -0.001614 0.000009 +vn -0.999999 -0.001611 0.000000 +vn -0.628164 -0.000000 -0.778081 +vn -0.944355 0.104600 -0.311853 +vn -0.901436 -0.000000 -0.432913 +vn -0.608806 0.773474 -0.176329 +vn 0.616344 0.570219 0.543112 +vn -0.178933 0.496218 0.849559 +vn -0.336067 0.926478 0.169402 +vn 0.326412 0.192288 0.925462 +vn -0.202222 -0.886786 0.415592 +vn 0.131097 -0.303651 0.943721 +vn 0.525411 -0.638120 0.562802 +vn -0.459420 -0.687735 0.562098 +vn -0.287476 -0.887075 -0.361187 +vn -0.432678 -0.718254 -0.544887 +vn -0.452460 0.701514 -0.550598 +vn -0.301712 0.879869 -0.367153 +vn -0.021542 0.999768 -0.000000 +vn -0.999832 -0.018320 -0.000006 +vn 0.737134 -0.424441 -0.525816 +vn 0.389168 0.588615 -0.708576 +vn 0.389168 0.588615 -0.708576 +vn 0.250198 0.244643 -0.936777 +vn 0.251011 -0.242045 -0.937234 +vn 0.737134 -0.424441 -0.525816 +vn 0.004436 0.999814 -0.018778 +vn 0.004436 0.999814 -0.018778 +vn 0.004436 0.999814 -0.018778 +vn 0.000000 0.999987 0.004994 +vn 0.000000 0.999987 0.004994 +vn 0.000000 0.999987 0.004994 +vn 0.000006 -0.999892 0.014681 +vn 0.000006 -0.999892 0.014681 +vn 0.000006 -0.999892 0.014681 +vn -0.004437 -0.999978 -0.004971 +vn -0.004437 -0.999978 -0.004971 +vn -0.004437 -0.999978 -0.004971 +vn 0.000010 0.002341 -0.999997 +vn 0.000010 0.002341 -0.999997 +vn 0.000010 0.002341 -0.999997 +vn 0.000010 0.002341 -0.999997 +vn 0.616344 0.570219 0.543112 +vn -0.019503 0.999797 0.004993 +vn -0.019503 0.999797 0.004993 +vn -0.019503 0.999797 0.004993 +vn 0.021541 -0.999756 -0.004970 +vn 0.021541 -0.999756 -0.004970 +vn 0.021541 -0.999756 -0.004970 +vn -0.999832 -0.018323 -0.000000 +vn 0.999832 0.018322 0.000000 +vn 0.999832 0.018322 -0.000027 +vn 0.999832 0.018322 -0.000027 +vn -0.028006 0.999607 -0.000674 +vn -0.028006 0.999607 -0.000674 +vn -0.028006 0.999607 -0.000674 +vn 0.021541 -0.999767 0.001458 +vn 0.021541 -0.999767 0.001458 +vn 0.021541 -0.999767 0.001458 +vn 0.026277 -0.999654 -0.000654 +vn 0.026277 -0.999654 -0.000654 +vn 0.026277 -0.999654 -0.000654 +vn 0.000000 -0.000001 -1.000000 +vn 0.000000 -0.000001 -1.000000 +vn 0.000000 -0.000001 -1.000000 +vn 0.000000 -0.000001 -1.000000 +vn 0.251011 -0.242045 -0.937234 +vn 0.250198 0.244643 -0.936777 +vn -0.999832 -0.018323 0.000012 +vn -0.999832 -0.018322 -0.000000 +vn -0.999832 -0.018323 0.000012 +vn 0.999832 0.018322 0.000000 +vn 0.999832 0.018322 0.000012 +vn 0.999832 0.018322 0.000012 +vn -0.021910 0.999760 -0.000674 +vn -0.016455 0.999865 0.000337 +vn -0.016455 0.999865 0.000337 +vn -0.016455 0.999865 0.000337 +vn 0.021541 -0.999768 -0.000654 +vn 0.021541 -0.999768 -0.000654 +vn 0.021541 -0.999768 -0.000654 +vn 0.014490 -0.999894 0.001458 +vn 0.014490 -0.999894 0.001458 +vn 0.014490 -0.999894 0.001458 +vn 0.000000 -0.000001 -1.000000 +vn 0.000000 -0.000001 -1.000000 +vn 0.000000 -0.000001 -1.000000 +vn 0.000000 -0.000001 -1.000000 +vn 0.999921 -0.012551 0.000071 +vn 0.999921 -0.012551 0.000071 +vn 0.999921 -0.012577 -0.000000 +vn 0.999921 -0.012551 0.000071 +vn 0.004437 0.999990 0.000000 +vn 0.004437 0.999990 0.000000 +vn 0.004437 0.999990 0.000000 +vn 0.004437 0.999990 0.000000 +vn 0.737493 -0.000000 -0.675355 +vn 0.929055 0.064665 -0.364246 +vn 0.909553 0.332232 -0.249671 +vn 0.967756 -0.000000 -0.251889 +vn -0.950141 0.000000 0.311822 +vn -0.754521 0.319338 0.573342 +vn -0.729449 0.645891 0.225231 +vn -0.379580 0.000000 0.925159 +vn -0.176656 0.422102 0.889169 +vn 0.201703 0.000000 0.979447 +vn 0.362436 0.382183 0.850045 +vn 0.798191 0.000000 0.602404 +vn 0.968028 0.109472 0.225694 +vn -0.171179 0.888219 0.426338 +vn 0.062881 0.915143 0.398194 +vn 0.465687 0.809125 0.358403 +vn 0.798191 0.000000 0.602404 +vn 0.465687 0.809125 0.358403 +vn -0.000000 -0.000000 -1.000000 +vn 0.000000 -0.000000 -1.000000 +vn 0.000000 -0.000000 -1.000000 +vn 0.000000 -0.000000 -1.000000 +vn 0.000000 -0.000000 -1.000000 +vn 0.000000 -0.000000 -1.000000 +vn 0.000000 -0.000000 -1.000000 +vn 0.000000 -0.000000 -1.000000 +vn 0.000000 -0.000000 -1.000000 +vn 0.000000 -0.000000 -1.000000 +vn 0.000000 -0.000000 -1.000000 +vn 0.000000 -0.000000 -1.000000 +vn 0.011725 0.985795 0.167542 +vn 0.909553 0.332232 -0.249671 +vn -0.005642 0.990634 0.136425 +vn -0.608806 0.773474 -0.176329 +vn -0.999745 0.022571 -0.000427 +vn -0.999745 0.022571 -0.000427 +vn -0.999745 0.022571 -0.000427 +vn -0.999971 -0.005425 0.005345 +vn -0.999971 -0.005425 0.005345 +vn -0.999971 -0.005425 0.005345 +vn -0.148086 0.988975 -0.000000 +vn -0.148086 0.988975 -0.000000 +vn -0.148086 0.988975 -0.000000 +vn -0.464450 0.885579 0.005999 +vn -0.464450 0.885579 0.005999 +vn -0.464450 0.885579 0.005999 +vn -0.847890 0.018688 0.529842 +vn -0.847890 0.018688 0.529842 +vn -0.847890 0.018688 0.529842 +vn -0.845153 0.019082 0.534183 +vn -0.845153 0.019082 0.534183 +vn -0.845153 0.019082 0.534183 +vn 0.000000 -0.000001 -1.000000 +vn 0.000000 -0.000001 -1.000000 +vn -0.999992 -0.004070 0.000000 +vn -0.999992 -0.004070 0.000000 +vn -0.999992 -0.004070 0.000000 +vn -0.999992 -0.004070 0.000000 +vn -0.000000 0.000000 1.000000 +vn -0.000000 0.000000 1.000000 +vn 0.999992 0.004076 -0.000000 +vn 0.999992 0.004076 0.000000 +vn 0.999992 0.004076 -0.000000 +vn 0.999992 0.004076 -0.000000 +vn -0.004429 0.913622 -0.406539 +vn -0.004429 0.913622 -0.406539 +vn -0.004429 0.913622 -0.406539 +vn -0.004027 0.907531 -0.419964 +vn -0.004027 0.907531 -0.419964 +vn -0.004027 0.907531 -0.419964 +vn -0.004381 0.903704 0.428136 +vn -0.004381 0.903704 0.428136 +vn -0.004381 0.903704 0.428136 +vn -0.004036 0.909589 0.415488 +vn -0.004036 0.909589 0.415488 +vn -0.004036 0.909589 0.415488 +vn -0.020304 0.999794 -0.000000 +vn -0.020305 0.999794 -0.000000 +vn -0.020304 0.999794 -0.000000 +vn -0.020304 0.999794 -0.000000 +vn 0.012824 0.999918 -0.000000 +vn 0.012824 0.999918 -0.000000 +vn 0.012824 0.999918 -0.000000 +vn 0.012824 0.999918 -0.000000 +vn -0.000000 0.000001 -1.000000 +vn -0.000000 0.000001 -1.000000 +vn -0.000000 0.000001 -1.000000 +vn -0.000000 0.000001 -1.000000 +vn 0.004437 -0.999990 0.000000 +vn 0.004437 -0.999990 0.000000 +vn 0.004437 -0.999990 0.000000 +vn 0.004437 -0.999990 0.000000 +vn -0.000000 0.000001 1.000000 +vn -0.000000 0.000001 1.000000 +vn -0.000000 0.000001 1.000000 +vn -0.000000 0.000001 1.000000 +vn -0.999469 0.018316 -0.026931 +vn -0.999469 0.018316 -0.026931 +vn -0.999469 0.018316 -0.026931 +vn -0.999469 0.018316 -0.026931 +vn 0.021530 0.999231 -0.032765 +vn 0.021530 0.999231 -0.032765 +vn 0.021530 0.999231 -0.032765 +vn 0.006116 0.999583 -0.028232 +vn 0.006116 0.999583 -0.028232 +vn 0.006116 0.999583 -0.028232 +vn 0.999329 -0.018313 -0.031720 +vn 0.999329 -0.018313 -0.031720 +vn 0.999329 -0.018313 -0.031720 +vn 0.999329 -0.018313 -0.031720 +vn -0.021533 -0.999381 -0.027818 +vn -0.021533 -0.999381 -0.027818 +vn -0.021533 -0.999381 -0.027818 +vn -0.039109 -0.998716 -0.032200 +vn -0.039109 -0.998716 -0.032200 +vn -0.039109 -0.998716 -0.032200 +vn -0.999329 0.018313 -0.031720 +vn -0.999329 0.018313 -0.031720 +vn -0.999329 0.018313 -0.031720 +vn -0.999329 0.018313 -0.031720 +vn 0.021533 0.999381 -0.027818 +vn 0.021533 0.999381 -0.027818 +vn 0.021533 0.999381 -0.027818 +vn 0.039108 0.998716 -0.032200 +vn 0.039108 0.998716 -0.032200 +vn 0.039108 0.998716 -0.032200 +vn 0.999469 -0.018316 -0.026931 +vn 0.999469 -0.018316 -0.026931 +vn 0.999469 -0.018316 -0.026931 +vn 0.999469 -0.018316 -0.026931 +vn -0.021530 -0.999231 -0.032765 +vn -0.021530 -0.999231 -0.032765 +vn -0.021530 -0.999231 -0.032765 +vn -0.006116 -0.999583 -0.028231 +vn -0.006116 -0.999583 -0.028231 +vn -0.006116 -0.999583 -0.028231 +vn 0.021541 0.999768 -0.000000 +vn 0.021541 0.999768 -0.000000 +vn 0.021541 0.999768 -0.000000 +vn -0.021714 -0.999764 0.000317 +vn -0.021714 -0.999764 0.000317 +vn -0.021542 -0.999768 0.000000 +vn 0.021542 0.999768 -0.000000 +vn 0.021541 0.999768 -0.000000 +vn 0.021541 0.999768 -0.000000 +vn -0.021910 -0.999760 -0.000674 +vn -0.021542 -0.999768 0.000000 +vn -0.021910 -0.999760 -0.000674 +vn -0.999832 0.018323 -0.000000 +vn -0.999832 0.018323 -0.000000 +vn -0.999832 0.018323 -0.000000 +vn 0.999832 -0.018322 0.000000 +vn 0.999832 -0.018322 0.000000 +vn 0.999832 -0.018322 0.000000 +vn -0.999832 0.018322 -0.000000 +vn -0.999832 0.018322 -0.000000 +vn -0.999832 0.018322 -0.000000 +vn 0.999832 -0.018322 0.000000 +vn 0.999832 -0.018322 0.000000 +vn 0.999832 -0.018322 0.000000 +vn 0.021541 0.999768 -0.000000 +vn 0.021541 0.999768 -0.000000 +vn 0.021541 0.999768 -0.000000 +vn 0.021541 0.999768 -0.000000 +vn 0.968686 -0.195526 0.153029 +vn 0.968686 -0.195526 0.153029 +vn 0.968686 -0.195526 0.153029 +vn 0.973794 -0.182610 0.135571 +vn 0.973794 -0.182610 0.135571 +vn 0.973794 -0.182610 0.135571 +vn 0.956360 -0.020938 -0.291439 +vn 0.956184 -0.021083 -0.292008 +vn 0.956360 -0.020938 -0.291439 +vn 0.956360 -0.020938 -0.291439 +vn 0.947601 -0.319455 0.000000 +vn 0.947601 -0.319455 0.000000 +vn 0.947601 -0.319455 0.000000 +vn 0.947601 -0.319455 0.000000 +vn 0.501241 -0.666644 0.551674 +vn 0.501241 -0.666644 0.551674 +vn 0.501241 -0.666644 0.551674 +vn 0.508598 -0.663687 0.548496 +vn 0.508598 -0.663687 0.548496 +vn 0.508598 -0.663687 0.548496 +vn 0.999757 -0.022044 0.000000 +vn 0.999757 -0.022044 0.000000 +vn 0.999757 -0.022044 0.000000 +vn 0.999757 -0.022044 0.000000 +vn 0.000000 0.000000 1.000000 +vn 0.000000 0.000000 1.000000 +vn 0.000000 0.000000 1.000000 +vn 0.000000 0.000000 1.000000 +vn 0.921437 -0.016886 0.388160 +vn 0.854236 -0.015654 0.519649 +vn 0.967760 -0.017734 0.251249 +vn 0.967760 -0.017734 0.251250 +vn 0.019763 0.917212 0.397908 +vn 0.018253 0.847154 0.531034 +vn 0.020806 0.965657 0.258986 +vn 0.020806 0.965657 0.258986 +vn -0.921438 0.016886 0.388159 +vn -0.854236 0.015654 0.519649 +vn -0.967760 0.017734 0.251249 +vn -0.967760 0.017734 0.251249 +vn -0.019762 -0.917212 0.397908 +vn -0.018253 -0.847154 0.531034 +vn -0.020806 -0.965657 0.258986 +vn -0.020806 -0.965657 0.258986 +vn 0.893681 -0.016377 0.448404 +vn 0.019147 0.888655 0.458176 +vn -0.893681 0.016377 0.448404 +vn -0.019147 -0.888655 0.458176 +vn 0.701700 0.674268 0.230173 +vn 0.712574 0.684717 0.152974 +vn 0.707594 0.679932 -0.192362 +vn 0.690072 0.663095 -0.290011 +vn -0.674165 0.701592 0.230801 +vn -0.684673 0.712527 0.153389 +vn -0.679869 0.707528 -0.192829 +vn -0.662945 0.689916 -0.290723 +vn 0.674165 -0.701592 0.230802 +vn 0.684673 -0.712527 0.153389 +vn 0.679869 -0.707528 -0.192828 +vn 0.662945 -0.689916 -0.290722 +vn -0.701699 -0.674269 0.230174 +vn -0.712573 -0.684717 0.152974 +vn -0.707594 -0.679932 -0.192362 +vn -0.690071 -0.663095 -0.290011 +vn 0.698442 -0.012799 -0.715552 +vn 0.698442 -0.012799 -0.715552 +vn 0.858479 -0.015732 -0.512607 +vn 0.014796 0.686711 -0.726780 +vn 0.014796 0.686712 -0.726779 +vn 0.018371 0.852614 -0.522219 +vn -0.698441 0.012799 -0.715553 +vn -0.698441 0.012799 -0.715553 +vn -0.858479 0.015732 -0.512607 +vn -0.014796 -0.686711 -0.726780 +vn -0.014796 -0.686711 -0.726780 +vn -0.018371 -0.852614 -0.522219 +vn 0.974379 -0.017856 0.224202 +vn 0.020969 0.973180 0.229088 +vn -0.974379 0.017856 0.224202 +vn -0.020969 -0.973180 0.229088 +vn 0.966434 -0.017711 -0.256303 +vn 0.020794 0.965085 -0.261109 +vn -0.966434 0.017710 -0.256304 +vn -0.020794 -0.965085 -0.261109 +vn 0.619054 -0.644240 0.449140 +vn 0.644657 0.619456 0.447986 +vn -0.644657 -0.619456 0.447987 +vn -0.619055 0.644239 0.449140 +vn 0.575750 -0.599173 -0.556331 +vn 0.599769 0.576323 -0.555094 +vn -0.599768 -0.576322 -0.555095 +vn -0.575749 0.599172 -0.556332 +vn 0.999832 -0.018322 0.000000 +vn 0.999832 -0.018322 0.000000 +vn 0.999832 -0.018322 0.000000 +vn 0.999832 -0.018322 0.000000 +vn 0.021541 0.999768 -0.000000 +vn 0.021541 0.999768 -0.000000 +vn 0.021541 0.999768 -0.000000 +vn 0.021541 0.999768 -0.000000 +vn -0.999832 0.018322 -0.000000 +vn -0.999832 0.018322 -0.000000 +vn -0.999832 0.018322 -0.000000 +vn -0.999832 0.018322 -0.000000 +vn -0.021541 -0.999768 0.000000 +vn -0.021541 -0.999768 0.000000 +vn -0.021541 -0.999768 0.000000 +vn -0.021541 -0.999768 0.000000 +vn 0.014158 0.657083 0.753685 +vn 0.014158 0.657082 0.753686 +vn 0.014158 0.657083 0.753685 +vn 0.014158 0.657083 0.753685 +vn 0.669174 -0.012263 0.743005 +vn 0.669174 -0.012263 0.743005 +vn 0.669174 -0.012263 0.743005 +vn 0.669174 -0.012263 0.743005 +vn -0.014158 -0.657082 0.753686 +vn -0.014158 -0.657082 0.753686 +vn -0.014158 -0.657082 0.753686 +vn -0.014158 -0.657082 0.753686 +vn -0.669173 0.012263 0.743005 +vn -0.669173 0.012263 0.743005 +vn -0.669173 0.012263 0.743005 +vn -0.669173 0.012263 0.743005 +vn 0.999999 -0.001050 0.000000 +vn 0.999999 -0.001050 0.000000 +vn 0.999999 -0.001050 0.000000 +vn 0.999999 -0.001050 0.000000 +vn -0.999999 0.001055 0.000000 +vn -0.999999 0.001055 0.000000 +vn -0.999999 0.001055 0.000000 +vn -0.999999 0.001055 0.000000 +vn 0.000000 -0.770164 0.637845 +vn 0.000000 -0.770164 0.637845 +vn 0.000000 -0.770164 0.637845 +vn -0.016619 -0.771290 0.636266 +vn -0.016619 -0.771290 0.636266 +vn -0.016619 -0.771290 0.636266 +vn 0.193431 0.981114 -0.000000 +vn 0.193431 0.981114 -0.000000 +vn 0.193431 0.981114 -0.000000 +vn 0.193431 0.981114 -0.000000 +vn 0.021301 0.988620 0.148918 +vn 0.021301 0.988620 0.148918 +vn 0.021301 0.988620 0.148918 +vn 0.021301 0.988620 0.148918 +vn -0.148086 0.988975 -0.000000 +vn 0.999832 -0.018322 0.000000 +vn 0.999832 -0.018322 0.000000 +vn 0.999832 -0.018322 0.000000 +vn 0.999760 -0.021888 -0.000000 +vn 0.999760 -0.021888 -0.000000 +vn 0.999760 -0.021888 -0.000000 +vn 0.999760 -0.021888 -0.000000 +vn -0.999757 0.022035 0.000000 +vn -0.999757 0.022035 0.000000 +vn -0.999757 0.022035 0.000000 +vn -0.999757 0.022035 0.000000 +vn -0.000211 -0.004415 -0.999990 +vn 0.000000 -0.004485 -0.999990 +vn -0.000211 -0.004415 -0.999990 +vn -0.000211 -0.004415 -0.999990 +vn 0.999832 -0.018322 0.000000 +vn 0.999832 -0.018322 0.000000 +vn -0.021541 -0.999768 0.000000 +vn -0.021541 -0.999768 0.000000 +vn -0.021541 -0.999768 0.000000 +vn -0.021714 -0.999764 0.000317 +vn -0.999832 0.018323 -0.000000 +vn -0.999832 0.018323 -0.000000 +vn -0.999832 0.018320 -0.000006 +vn -0.999832 0.018322 0.000000 +vn -0.999999 0.001611 0.000000 +vn -0.999999 0.001614 0.000009 +vn -0.999999 0.001611 0.000000 +vn -0.999999 0.001611 0.000000 +vn -0.944355 -0.104600 -0.311853 +vn -0.608807 -0.773474 -0.176329 +vn 0.616344 -0.570219 0.543112 +vn -0.336067 -0.926478 0.169402 +vn -0.178933 -0.496218 0.849559 +vn 0.326412 -0.192288 0.925462 +vn -0.202221 0.886786 0.415592 +vn 0.525411 0.638120 0.562802 +vn 0.131097 0.303651 0.943721 +vn -0.459420 0.687735 0.562098 +vn -0.287476 0.887075 -0.361187 +vn -0.432678 0.718253 -0.544887 +vn -0.301712 -0.879869 -0.367153 +vn -0.452459 -0.701514 -0.550598 +vn -0.021541 -0.999768 0.000000 +vn -0.999832 0.018320 -0.000006 +vn 0.737134 0.424441 -0.525816 +vn 0.389168 -0.588615 -0.708576 +vn 0.389168 -0.588615 -0.708576 +vn 0.250198 -0.244643 -0.936777 +vn 0.251011 0.242045 -0.937234 +vn 0.737134 0.424441 -0.525816 +vn 0.004436 -0.999814 -0.018777 +vn 0.004436 -0.999814 -0.018777 +vn 0.004436 -0.999814 -0.018777 +vn 0.000000 -0.999987 0.004994 +vn 0.000000 -0.999987 0.004994 +vn 0.000000 -0.999987 0.004994 +vn 0.000006 0.999892 0.014681 +vn 0.000006 0.999892 0.014681 +vn 0.000006 0.999892 0.014681 +vn -0.004437 0.999978 -0.004971 +vn -0.004437 0.999978 -0.004971 +vn -0.004437 0.999978 -0.004971 +vn 0.000010 -0.002341 -0.999997 +vn 0.000010 -0.002341 -0.999997 +vn 0.000010 -0.002341 -0.999997 +vn 0.000010 -0.002341 -0.999997 +vn 0.616344 -0.570219 0.543112 +vn -0.019503 -0.999797 0.004993 +vn -0.019503 -0.999797 0.004993 +vn -0.019503 -0.999797 0.004993 +vn 0.021541 0.999756 -0.004970 +vn 0.021541 0.999756 -0.004970 +vn 0.021541 0.999756 -0.004970 +vn -0.999832 0.018323 -0.000000 +vn 0.999832 -0.018322 0.000000 +vn 0.999832 -0.018322 -0.000027 +vn 0.999832 -0.018322 -0.000027 +vn -0.028006 -0.999607 -0.000674 +vn -0.028006 -0.999607 -0.000674 +vn -0.028006 -0.999607 -0.000674 +vn 0.021541 0.999767 0.001458 +vn 0.021541 0.999767 0.001458 +vn 0.021541 0.999767 0.001458 +vn 0.026277 0.999654 -0.000654 +vn 0.026277 0.999654 -0.000654 +vn 0.026277 0.999654 -0.000654 +vn 0.000000 0.000001 -1.000000 +vn 0.000000 0.000001 -1.000000 +vn 0.000000 0.000001 -1.000000 +vn 0.000000 0.000001 -1.000000 +vn 0.251011 0.242045 -0.937234 +vn 0.250198 -0.244643 -0.936777 +vn -0.999832 0.018322 -0.000000 +vn -0.999832 0.018323 0.000012 +vn -0.999832 0.018323 0.000012 +vn 0.999832 -0.018322 0.000000 +vn 0.999832 -0.018322 0.000012 +vn 0.999832 -0.018322 0.000012 +vn -0.021910 -0.999760 -0.000674 +vn -0.016454 -0.999865 0.000337 +vn -0.016454 -0.999865 0.000337 +vn -0.016454 -0.999865 0.000337 +vn 0.021541 0.999768 -0.000654 +vn 0.021541 0.999768 -0.000654 +vn 0.021541 0.999768 -0.000654 +vn 0.014490 0.999894 0.001458 +vn 0.014490 0.999894 0.001458 +vn 0.014490 0.999894 0.001458 +vn 0.000000 0.000001 -1.000000 +vn 0.000000 0.000001 -1.000000 +vn 0.000000 0.000001 -1.000000 +vn 0.000000 0.000001 -1.000000 +vn 0.999921 0.012551 0.000071 +vn 0.999921 0.012577 -0.000000 +vn 0.999921 0.012551 0.000071 +vn 0.999921 0.012551 0.000071 +vn 0.004437 -0.999990 0.000000 +vn 0.004437 -0.999990 0.000000 +vn 0.004437 -0.999990 0.000000 +vn 0.004437 -0.999990 0.000000 +vn 0.909553 -0.332232 -0.249671 +vn 0.929055 -0.064665 -0.364246 +vn -0.754521 -0.319338 0.573342 +vn -0.729449 -0.645891 0.225232 +vn -0.176656 -0.422102 0.889170 +vn 0.362436 -0.382183 0.850045 +vn 0.968028 -0.109472 0.225694 +vn -0.171179 -0.888219 0.426339 +vn 0.062881 -0.915143 0.398194 +vn 0.465687 -0.809125 0.358404 +vn 0.465687 -0.809125 0.358404 +vn -0.000000 -0.000000 -1.000000 +vn -0.000000 -0.000000 -1.000000 +vn -0.000000 -0.000000 -1.000000 +vn -0.000000 -0.000000 -1.000000 +vn -0.000000 -0.000000 -1.000000 +vn -0.000000 -0.000000 -1.000000 +vn 0.011725 -0.985795 0.167542 +vn 0.909553 -0.332232 -0.249671 +vn -0.005642 -0.990634 0.136425 +vn -0.608807 -0.773474 -0.176329 +f 1/1/1 2/2/2 3/3/3 +f 4/4/4 5/5/5 6/6/6 +f 7/7/7 8/8/8 9/9/9 +f 10/10/10 11/11/11 12/12/12 +f 13/13/13 14/14/14 15/15/15 +f 16/16/16 17/17/17 18/18/18 +f 19/19/19 20/20/20 21/21/21 +f 20/20/20 19/19/19 22/22/22 +f 23/23/23 24/24/24 25/25/25 +f 24/24/24 23/23/23 26/26/26 +f 27/27/27 28/28/28 29/29/29 +f 28/28/28 27/27/27 30/30/30 +f 31/31/31 32/32/32 33/33/33 +f 32/32/32 31/31/31 34/34/34 +f 35/35/35 36/36/36 37/37/37 +f 38/38/38 39/39/39 40/40/40 +f 41/41/41 42/42/42 43/43/43 +f 44/44/44 45/45/45 46/46/46 +f 47/47/47 48/48/48 49/49/49 +f 48/48/48 47/47/47 50/50/50 +f 51/51/51 52/52/52 53/53/53 +f 52/52/52 51/51/51 54/54/54 +f 55/55/55 56/56/56 57/57/57 +f 56/56/56 55/55/55 58/58/58 +f 59/59/59 60/60/60 61/61/61 +f 60/60/60 59/59/59 62/62/62 +f 63/63/63 64/64/64 65/65/65 +f 64/64/64 63/63/63 66/66/66 +f 67/67/67 68/68/68 69/69/69 +f 68/68/68 67/67/67 70/70/70 +f 71/71/71 72/72/72 73/73/73 +f 74/74/74 75/75/75 76/76/76 +f 77/77/77 78/78/78 79/79/79 +f 78/78/78 77/77/77 80/80/80 +f 81/81/81 82/82/82 83/83/83 +f 84/84/84 85/85/85 86/86/86 +f 87/87/87 88/88/88 89/89/89 +f 88/88/88 87/87/87 90/90/90 +f 91/91/91 92/92/92 93/93/93 +f 94/94/94 95/95/95 96/96/96 +f 97/97/97 98/98/98 99/99/99 +f 98/98/98 97/97/97 100/100/100 +f 101/101/101 102/102/102 103/103/103 +f 104/104/104 105/105/105 106/106/106 +f 107/107/107 108/108/108 109/109/109 +f 110/110/110 111/111/111 112/112/112 +f 113/113/113 114/114/114 115/115/115 +f 116/116/116 117/117/117 118/118/118 +f 119/119/119 120/120/120 121/121/121 +f 122/122/122 123/123/123 124/124/124 +f 125/125/125 126/126/126 127/127/127 +f 128/128/128 129/129/129 130/130/130 +f 115/115/115 131/131/131 113/113/113 +f 131/131/131 115/115/115 132/132/132 +f 107/107/107 133/133/133 108/108/108 +f 133/133/133 107/107/107 134/134/134 +f 135/135/135 136/136/136 137/137/137 +f 138/138/138 139/139/139 140/140/140 +f 141/141/141 142/142/142 143/143/143 +f 142/142/142 141/141/141 144/144/144 +f 145/145/145 146/146/146 147/147/147 +f 146/146/146 145/145/145 148/148/148 +f 149/149/149 150/150/150 151/151/151 +f 152/152/152 153/153/153 154/154/154 +f 155/155/155 156/156/156 157/157/157 +f 158/158/158 157/157/157 156/156/156 +f 159/159/159 160/160/160 161/161/161 +f 160/160/160 159/159/159 162/162/162 +f 163/163/163 164/164/164 165/165/165 +f 164/164/164 163/163/163 166/166/166 +f 167/167/167 168/168/168 169/169/169 +f 168/168/168 167/167/167 170/170/170 +f 171/171/171 172/172/172 173/173/173 +f 172/172/172 171/171/171 174/174/174 +f 175/175/175 176/176/176 177/177/177 +f 176/176/176 175/175/175 178/178/178 +f 165/165/165 179/179/179 163/163/163 +f 169/169/169 180/180/180 167/167/167 +f 173/173/173 181/181/181 171/171/171 +f 177/177/177 182/182/182 175/175/175 +f 183/183/183 184/184/184 185/185/185 +f 186/186/186 185/185/185 184/184/184 +f 187/187/187 188/188/188 189/189/189 +f 190/190/190 189/189/189 188/188/188 +f 191/191/191 192/192/192 193/193/193 +f 194/194/194 193/193/193 192/192/192 +f 195/195/195 196/196/196 197/197/197 +f 198/198/198 197/197/197 196/196/196 +f 199/199/199 200/200/200 201/201/201 +f 202/202/202 203/203/203 204/204/204 +f 205/205/205 206/206/206 207/207/207 +f 208/208/208 209/209/209 210/210/210 +f 179/179/179 165/165/165 211/211/211 +f 180/180/180 169/169/169 212/212/212 +f 181/181/181 173/173/173 213/213/213 +f 182/182/182 177/177/177 214/214/214 +f 200/200/200 199/199/199 215/215/215 +f 203/203/203 202/202/202 216/216/216 +f 206/206/206 205/205/205 217/217/217 +f 209/209/209 208/208/208 218/218/218 +f 219/219/219 191/191/191 193/193/193 +f 183/183/183 185/185/185 220/220/220 +f 195/195/195 197/197/197 221/221/221 +f 187/187/187 189/189/189 222/222/222 +f 192/192/192 223/223/223 194/194/194 +f 224/224/224 186/186/186 184/184/184 +f 225/225/225 198/198/198 196/196/196 +f 226/226/226 190/190/190 188/188/188 +f 211/211/211 215/215/215 179/179/179 +f 215/215/215 211/211/211 200/200/200 +f 212/212/212 216/216/216 180/180/180 +f 216/216/216 212/212/212 203/203/203 +f 213/213/213 217/217/217 181/181/181 +f 217/217/217 213/213/213 206/206/206 +f 214/214/214 218/218/218 182/182/182 +f 218/218/218 214/214/214 209/209/209 +f 227/227/227 228/228/228 229/229/229 +f 228/228/228 227/227/227 230/230/230 +f 231/231/231 232/232/232 233/233/233 +f 232/232/232 231/231/231 234/234/234 +f 235/235/235 236/236/236 237/237/237 +f 236/236/236 235/235/235 238/238/238 +f 239/239/239 240/240/240 241/241/241 +f 240/240/240 239/239/239 242/242/242 +f 243/243/243 244/244/244 245/245/245 +f 244/244/244 243/243/243 246/246/246 +f 247/247/247 248/248/248 249/249/249 +f 248/248/248 247/247/247 250/250/250 +f 251/251/251 252/252/252 253/253/253 +f 252/252/252 251/251/251 254/254/254 +f 255/255/255 256/256/256 257/257/257 +f 256/256/256 255/255/255 258/258/258 +f 259/259/259 260/260/260 261/261/261 +f 260/260/260 259/259/259 262/262/262 +f 263/263/263 264/264/264 265/265/265 +f 264/264/264 263/263/263 266/266/266 +f 267/267/267 268/268/268 269/269/269 +f 270/270/270 271/271/271 272/272/272 +f 273/273/273 274/274/274 275/275/275 +f 274/274/274 273/273/273 276/276/276 +f 277/277/277 278/278/278 279/279/279 +f 278/278/278 277/277/277 280/280/280 +f 8/8/8 7/7/7 281/281/281 +f 282/282/282 283/283/283 284/284/284 +f 285/285/285 286/286/286 287/287/287 +f 286/286/286 285/285/285 288/288/288 +f 289/289/289 290/290/290 291/291/291 +f 290/290/290 289/289/289 292/292/292 +f 293/293/293 294/294/294 295/295/295 +f 294/294/294 293/293/293 296/296/296 +f 282/282/282 297/297/297 283/283/283 +f 297/297/297 282/282/282 298/298/298 +f 299/299/299 300/300/300 301/301/301 +f 300/300/300 299/299/299 302/302/302 +f 303/303/303 304/304/304 305/305/305 +f 304/304/304 303/303/303 306/306/306 +f 307/307/307 308/308/308 309/309/309 +f 308/308/308 307/307/307 310/310/310 +f 311/311/311 312/312/312 313/313/313 +f 312/312/312 311/311/311 314/314/314 +f 315/315/315 316/316/316 317/317/317 +f 316/316/316 315/315/315 318/318/318 +f 319/319/319 320/320/320 321/321/321 +f 320/320/320 319/319/319 322/322/322 +f 321/321/321 318/318/318 315/315/315 +f 318/318/318 321/321/321 320/320/320 +f 320/320/320 316/316/316 318/318/318 +f 316/316/316 320/320/320 322/322/322 +f 323/323/323 322/322/322 319/319/319 +f 322/322/322 323/323/323 324/324/324 +f 317/317/317 325/325/325 326/326/326 +f 325/325/325 317/317/317 316/316/316 +f 302/302/302 327/327/327 300/300/300 +f 304/304/304 306/306/306 328/328/328 +f 315/315/315 329/329/329 321/321/321 +f 329/329/329 315/315/315 330/330/330 +f 331/331/331 325/325/325 332/332/332 +f 325/325/325 331/331/331 326/326/326 +f 333/333/333 323/323/323 334/334/334 +f 323/323/323 333/333/333 324/324/324 +f 335/335/335 336/336/336 337/337/337 +f 338/338/338 339/339/339 340/340/340 +f 341/341/341 342/342/342 343/343/343 +f 344/344/344 345/345/345 346/346/346 +f 347/347/347 348/348/348 349/349/349 +f 348/348/348 347/347/347 350/350/350 +f 321/321/321 323/323/323 319/319/319 +f 323/323/323 321/321/321 334/334/334 +f 317/317/317 331/331/331 351/351/351 +f 331/331/331 317/317/317 326/326/326 +f 352/352/352 353/353/353 354/354/354 +f 355/355/355 356/356/356 357/357/357 +f 119/119/119 328/328/328 358/358/358 +f 328/328/328 119/119/119 304/304/304 +f 359/359/359 360/360/360 122/122/122 +f 360/360/360 359/359/359 361/361/361 +f 112/112/112 302/302/302 110/110/110 +f 362/362/362 363/363/363 364/364/364 +f 365/365/365 366/366/366 367/367/367 +f 368/368/368 369/369/369 370/370/370 +f 359/359/359 122/122/122 124/124/124 +f 120/120/120 119/119/119 358/358/358 +f 371/371/371 372/372/372 373/373/373 +f 372/372/372 371/371/371 374/374/374 +f 375/375/375 330/330/330 376/376/376 +f 330/330/330 375/375/375 329/329/329 +f 125/125/125 377/377/377 378/378/378 +f 377/377/377 125/125/125 379/379/379 +f 380/380/380 381/381/381 128/128/128 +f 381/381/381 380/380/380 382/382/382 +f 116/116/116 383/383/383 117/117/117 +f 384/384/384 385/385/385 386/386/386 +f 387/387/387 388/388/388 389/389/389 +f 390/390/390 391/391/391 392/392/392 +f 380/380/380 128/128/128 130/130/130 +f 126/126/126 125/125/125 378/378/378 +f 393/393/393 394/394/394 395/395/395 +f 394/394/394 393/393/393 396/396/396 +f 397/397/397 398/398/398 399/399/399 +f 398/398/398 397/397/397 400/400/400 +f 401/401/401 402/402/402 403/403/403 +f 402/402/402 401/401/401 404/404/404 +f 405/405/405 406/406/406 407/407/407 +f 406/406/406 405/405/405 408/408/408 +f 409/409/409 312/312/312 410/410/410 +f 312/312/312 409/409/409 313/313/313 +f 411/411/411 312/312/312 314/314/314 +f 312/312/312 411/411/411 410/410/410 +f 412/412/412 410/410/410 413/413/413 +f 410/410/410 412/412/412 409/409/409 +f 414/414/414 413/413/413 415/415/415 +f 413/413/413 414/414/414 412/412/412 +f 416/416/416 415/415/415 417/417/417 +f 415/415/415 416/416/416 414/414/414 +f 418/418/418 410/410/410 411/411/411 +f 410/410/410 418/418/418 413/413/413 +f 419/419/419 413/413/413 418/418/418 +f 413/413/413 419/419/419 415/415/415 +f 420/420/420 415/415/415 419/419/419 +f 415/415/415 420/420/420 417/417/417 +f 408/408/408 417/417/417 406/406/406 +f 417/417/417 408/408/408 421/421/421 +f 407/407/407 417/417/417 422/422/422 +f 417/417/417 407/407/407 406/406/406 +f 423/423/423 424/424/424 425/425/425 +f 424/424/424 423/423/423 426/426/426 +f 427/427/427 428/428/428 429/429/429 +f 428/428/428 427/427/427 430/430/430 +f 431/431/431 432/432/432 433/433/433 +f 432/432/432 431/431/431 434/434/434 +f 435/435/435 422/422/422 419/419/419 +f 422/422/422 435/435/435 436/436/436 +f 437/437/437 419/419/419 418/418/418 +f 419/419/419 437/437/437 435/435/435 +f 438/438/438 418/418/418 411/411/411 +f 418/418/418 438/438/438 437/437/437 +f 439/439/439 440/440/440 441/441/441 +f 442/442/442 443/443/443 444/444/444 +f 445/445/445 446/446/446 447/447/447 +f 448/448/448 449/449/449 450/450/450 +f 451/451/451 452/452/452 453/453/453 +f 454/454/454 455/455/455 456/456/456 +f 19/19/19 21/21/21 457/457/457 +f 457/457/457 458/458/458 19/19/19 +f 459/459/459 460/460/460 461/461/461 +f 461/461/461 462/462/462 459/459/459 +f 27/27/27 29/29/29 463/463/463 +f 463/463/463 464/464/464 27/27/27 +f 465/465/465 466/466/466 467/467/467 +f 467/467/467 468/468/468 465/465/465 +f 469/469/469 470/470/470 471/471/471 +f 472/472/472 473/473/473 474/474/474 +f 475/475/475 476/476/476 477/477/477 +f 478/478/478 479/479/479 480/480/480 +f 481/481/481 482/482/482 483/483/483 +f 483/483/483 484/484/484 481/481/481 +f 485/485/485 486/486/486 487/487/487 +f 487/487/487 488/488/488 485/485/485 +f 489/489/489 490/490/490 491/491/491 +f 491/491/491 492/492/492 489/489/489 +f 493/493/493 494/494/494 495/495/495 +f 495/495/495 496/496/496 493/493/493 +f 497/497/497 498/498/498 499/499/499 +f 499/499/499 500/500/500 497/497/497 +f 501/501/501 502/502/502 503/503/503 +f 503/503/503 504/504/504 501/501/501 +f 505/505/505 506/506/506 507/507/507 +f 508/508/508 509/509/509 510/510/510 +f 511/511/511 512/512/512 513/513/513 +f 513/513/513 514/514/514 511/511/511 +f 515/515/515 516/516/516 517/517/517 +f 518/518/518 519/519/519 520/520/520 +f 521/521/521 522/522/522 523/523/523 +f 523/523/523 524/524/524 521/521/521 +f 525/525/525 526/526/526 527/527/527 +f 528/528/528 529/529/529 530/530/530 +f 531/531/531 532/532/532 533/533/533 +f 533/533/533 534/534/534 531/531/531 +f 535/535/535 536/536/536 537/537/537 +f 538/538/538 539/539/539 540/540/540 +f 541/541/541 542/542/542 543/543/543 +f 544/544/544 545/545/545 546/546/546 +f 547/547/547 548/548/548 549/549/549 +f 550/550/550 551/551/551 552/552/552 +f 553/553/553 554/554/554 555/555/555 +f 556/556/556 557/557/557 558/558/558 +f 559/559/559 560/560/560 561/561/561 +f 562/562/562 563/563/563 564/564/564 +f 548/548/548 547/547/547 565/565/565 +f 565/565/565 566/566/566 548/548/548 +f 541/541/541 543/543/543 567/567/567 +f 567/567/567 568/568/568 541/541/541 +f 569/569/569 570/570/570 571/571/571 +f 572/572/572 573/573/573 574/574/574 +f 575/575/575 576/576/576 577/577/577 +f 577/577/577 578/578/578 575/575/575 +f 579/579/579 580/580/580 581/581/581 +f 581/581/581 582/582/582 579/579/579 +f 583/583/583 584/584/584 585/585/585 +f 586/586/586 587/587/587 588/588/588 +f 589/589/589 590/590/590 591/591/591 +f 592/592/592 591/591/591 590/590/590 +f 593/593/593 594/594/594 595/595/595 +f 595/595/595 596/596/596 593/593/593 +f 597/597/597 598/598/598 599/599/599 +f 599/599/599 600/600/600 597/597/597 +f 601/601/601 602/602/602 603/603/603 +f 603/603/603 604/604/604 601/601/601 +f 605/605/605 606/606/606 607/607/607 +f 607/607/607 608/608/608 605/605/605 +f 609/609/609 610/610/610 611/611/611 +f 611/611/611 612/612/612 609/609/609 +f 598/598/598 597/597/597 613/613/613 +f 602/602/602 601/601/601 614/614/614 +f 606/606/606 605/605/605 615/615/615 +f 610/610/610 609/609/609 616/616/616 +f 617/617/617 618/618/618 619/619/619 +f 620/620/620 619/619/619 618/618/618 +f 621/621/621 622/622/622 623/623/623 +f 624/624/624 623/623/623 622/622/622 +f 625/625/625 626/626/626 627/627/627 +f 628/628/628 627/627/627 626/626/626 +f 629/629/629 630/630/630 631/631/631 +f 632/632/632 631/631/631 630/630/630 +f 633/633/633 634/634/634 635/635/635 +f 636/636/636 637/637/637 638/638/638 +f 639/639/639 640/640/640 641/641/641 +f 642/642/642 643/643/643 644/644/644 +f 613/613/613 645/645/645 598/598/598 +f 614/614/614 646/646/646 602/602/602 +f 615/615/615 647/647/647 606/606/606 +f 616/616/616 648/648/648 610/610/610 +f 635/635/635 649/649/649 633/633/633 +f 638/638/638 650/650/650 636/636/636 +f 641/641/641 651/651/651 639/639/639 +f 644/644/644 652/652/652 642/642/642 +f 653/653/653 626/626/626 625/625/625 +f 617/617/617 654/654/654 618/618/618 +f 629/629/629 655/655/655 630/630/630 +f 621/621/621 656/656/656 622/622/622 +f 627/627/627 628/628/628 657/657/657 +f 658/658/658 619/619/619 620/620/620 +f 659/659/659 631/631/631 632/632/632 +f 660/660/660 623/623/623 624/624/624 +f 645/645/645 613/613/613 649/649/649 +f 649/649/649 635/635/635 645/645/645 +f 646/646/646 614/614/614 650/650/650 +f 650/650/650 638/638/638 646/646/646 +f 647/647/647 615/615/615 651/651/651 +f 651/651/651 641/641/641 647/647/647 +f 648/648/648 616/616/616 652/652/652 +f 652/652/652 644/644/644 648/648/648 +f 661/661/661 662/662/662 663/663/663 +f 663/663/663 664/664/664 661/661/661 +f 665/665/665 666/666/666 667/667/667 +f 667/667/667 668/668/668 665/665/665 +f 669/669/669 670/670/670 671/671/671 +f 671/671/671 672/672/672 669/669/669 +f 673/673/673 674/674/674 675/675/675 +f 675/675/675 676/676/676 673/673/673 +f 677/677/677 678/678/678 679/679/679 +f 679/679/679 680/680/680 677/677/677 +f 681/681/681 682/682/682 683/683/683 +f 683/683/683 684/684/684 681/681/681 +f 685/685/685 686/686/686 687/687/687 +f 687/687/687 688/688/688 685/685/685 +f 689/689/689 690/690/690 691/691/691 +f 691/691/691 692/692/692 689/689/689 +f 693/693/693 694/694/694 695/695/695 +f 695/695/695 696/696/696 693/693/693 +f 697/697/697 698/698/698 699/699/699 +f 699/699/699 700/700/700 697/697/697 +f 701/701/701 702/702/702 703/703/703 +f 704/704/704 705/705/705 706/706/706 +f 707/707/707 708/708/708 709/709/709 +f 709/709/709 710/710/710 707/707/707 +f 711/711/711 712/712/712 713/713/713 +f 713/713/713 714/714/714 711/711/711 +f 447/447/447 715/715/715 445/445/445 +f 716/716/716 717/717/717 718/718/718 +f 719/719/719 720/720/720 721/721/721 +f 721/721/721 722/722/722 719/719/719 +f 723/723/723 724/724/724 725/725/725 +f 725/725/725 726/726/726 723/723/723 +f 727/727/727 728/728/728 729/729/729 +f 729/729/729 730/730/730 727/727/727 +f 716/716/716 718/718/718 731/731/731 +f 731/731/731 732/732/732 716/716/716 +f 733/733/733 734/734/734 735/735/735 +f 735/735/735 736/736/736 733/733/733 +f 737/737/737 738/738/738 739/739/739 +f 739/739/739 740/740/740 737/737/737 +f 741/741/741 742/742/742 743/743/743 +f 743/743/743 744/744/744 741/741/741 +f 311/311/311 313/313/313 745/745/745 +f 745/745/745 746/746/746 311/311/311 +f 747/747/747 748/748/748 749/749/749 +f 749/749/749 750/750/750 747/747/747 +f 751/751/751 752/752/752 753/753/753 +f 753/753/753 754/754/754 751/751/751 +f 752/752/752 747/747/747 750/750/750 +f 750/750/750 753/753/753 752/752/752 +f 753/753/753 750/750/750 749/749/749 +f 749/749/749 754/754/754 753/753/753 +f 755/755/755 751/751/751 754/754/754 +f 754/754/754 756/756/756 755/755/755 +f 748/748/748 757/757/757 758/758/758 +f 758/758/758 749/749/749 748/748/748 +f 736/736/736 735/735/735 759/759/759 +f 739/739/739 760/760/760 740/740/740 +f 747/747/747 752/752/752 761/761/761 +f 761/761/761 762/762/762 747/747/747 +f 763/763/763 764/764/764 758/758/758 +f 758/758/758 757/757/757 763/763/763 +f 765/765/765 766/766/766 755/755/755 +f 755/755/755 756/756/756 765/765/765 +f 767/767/767 768/768/768 769/769/769 +f 770/770/770 771/771/771 772/772/772 +f 773/773/773 774/774/774 775/775/775 +f 776/776/776 777/777/777 778/778/778 +f 779/779/779 780/780/780 781/781/781 +f 781/781/781 782/782/782 779/779/779 +f 752/752/752 751/751/751 755/755/755 +f 755/755/755 766/766/766 752/752/752 +f 748/748/748 783/783/783 763/763/763 +f 763/763/763 757/757/757 748/748/748 +f 784/784/784 785/785/785 786/786/786 +f 787/787/787 788/788/788 789/789/789 +f 553/553/553 790/790/790 760/760/760 +f 760/760/760 739/739/739 553/553/553 +f 791/791/791 556/556/556 792/792/792 +f 792/792/792 793/793/793 791/791/791 +f 545/545/545 544/544/544 736/736/736 +f 794/794/794 795/795/795 796/796/796 +f 797/797/797 798/798/798 799/799/799 +f 800/800/800 801/801/801 802/802/802 +f 791/791/791 557/557/557 556/556/556 +f 555/555/555 790/790/790 553/553/553 +f 803/803/803 804/804/804 805/805/805 +f 805/805/805 806/806/806 803/803/803 +f 807/807/807 808/808/808 762/762/762 +f 762/762/762 761/761/761 807/807/807 +f 559/559/559 809/809/809 810/810/810 +f 810/810/810 811/811/811 559/559/559 +f 812/812/812 562/562/562 813/813/813 +f 813/813/813 814/814/814 812/812/812 +f 550/550/550 552/552/552 815/815/815 +f 816/816/816 817/817/817 818/818/818 +f 819/819/819 820/820/820 821/821/821 +f 822/822/822 823/823/823 824/824/824 +f 812/812/812 563/563/563 562/562/562 +f 561/561/561 809/809/809 559/559/559 +f 825/825/825 826/826/826 827/827/827 +f 827/827/827 828/828/828 825/825/825 +f 829/829/829 830/830/830 831/831/831 +f 831/831/831 832/832/832 829/829/829 +f 833/833/833 834/834/834 835/835/835 +f 835/835/835 836/836/836 833/833/833 +f 405/405/405 837/837/837 838/838/838 +f 838/838/838 408/408/408 405/405/405 +f 409/409/409 839/839/839 745/745/745 +f 745/745/745 313/313/313 409/409/409 +f 840/840/840 746/746/746 745/745/745 +f 745/745/745 839/839/839 840/840/840 +f 412/412/412 841/841/841 839/839/839 +f 839/839/839 409/409/409 412/412/412 +f 414/414/414 842/842/842 841/841/841 +f 841/841/841 412/412/412 414/414/414 +f 416/416/416 843/843/843 842/842/842 +f 842/842/842 414/414/414 416/416/416 +f 844/844/844 840/840/840 839/839/839 +f 839/839/839 841/841/841 844/844/844 +f 845/845/845 844/844/844 841/841/841 +f 841/841/841 842/842/842 845/845/845 +f 846/846/846 845/845/845 842/842/842 +f 842/842/842 843/843/843 846/846/846 +f 408/408/408 838/838/838 843/843/843 +f 843/843/843 421/421/421 408/408/408 +f 837/837/837 847/847/847 843/843/843 +f 843/843/843 838/838/838 837/837/837 +f 423/423/423 425/425/425 848/848/848 +f 848/848/848 849/849/849 423/423/423 +f 427/427/427 850/850/850 851/851/851 +f 851/851/851 430/430/430 427/427/427 +f 431/431/431 433/433/433 852/852/852 +f 852/852/852 853/853/853 431/431/431 +f 854/854/854 845/845/845 847/847/847 +f 847/847/847 855/855/855 854/854/854 +f 856/856/856 844/844/844 845/845/845 +f 845/845/845 854/854/854 856/856/856 +f 857/857/857 840/840/840 844/844/844 +f 844/844/844 856/856/856 857/857/857 diff --git a/convex_decomposition/ConvexDecomposition/readme.txt b/convex_decomposition/ConvexDecomposition/readme.txt new file mode 100644 index 0000000..d687f13 --- /dev/null +++ b/convex_decomposition/ConvexDecomposition/readme.txt @@ -0,0 +1,75 @@ + +ConvexDecomposition library written by John W. Ratcliff + +Usage: Test (options) + +Options: + + -d : How deep to recursively split. Values of 3-7 are reasonable. + -c : Percentage of concavity to keep splitting. 0-20 4324640s reasonable. + -p : Percentage of volume delta to collapse hulls. 0-30 4324544s reasonable. + -v : Maximum number of vertices in the output hull. Default is 32. + -s : Skin Width inflation. Default is 0.0 + +To run the sample provided with defaults: + +DecomposeSample chair.obj + +Will produce 'chair_convex.obj' a Wavefront OBJ file useful for debug visualization. + 'chair.dae' a COLLADA physics representation of the model. + 'chair.xml' an Ageia PhysX NxuStream representation of the model. + + +/*! +** +** Copyright (c) 2007 by John W. Ratcliff mailto:jratcliff@infiniplex.net +** +** Portions of this source has been released with the PhysXViewer application, as well as +** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. +** +** If you find this code useful or you are feeling particularily generous I would +** ask that you please go to http://www.amillionpixels.us and make a donation +** to Troy DeMolay. +** +** DeMolay is a youth group for young men between the ages of 12 and 21. +** It teaches strong moral principles, as well as leadership skills and +** public speaking. The donations page uses the 'pay for pixels' paradigm +** where, in this case, a pixel is only a single penny. Donations can be +** made for as small as $4 or as high as a $100 block. Each person who donates +** will get a link to their own site as well as acknowledgement on the +** donations blog located here http://www.amillionpixels.blogspot.com/ +** +** If you wish to contact me you can use the following methods: +** +** Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) +** Skype ID: jratcliff63367 +** Yahoo: jratcliff63367 +** AOL: jratcliff1961 +** email: jratcliff@infiniplex.net +** Personal website: http://jratcliffscarab.blogspot.com +** Coding Website: http://codesuppository.blogspot.com +** FundRaising Blog: http://amillionpixels.blogspot.com +** Fundraising site: http://www.amillionpixels.us +** New Temple Site: http://newtemple.blogspot.com +** +** +** The MIT license: +** +** Permission is hereby granted, free of charge, to any person obtaining a copy +** of this software and associated documentation files (the "Software"), to deal +** in the Software without restriction, including without limitation the rights +** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +** copies of the Software, and to permit persons to whom the Software is furnished +** to do so, subject to the following conditions: +** +** The above copyright notice and this permission notice shall be included in all +** copies or substantial portions of the Software. + +** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +*/ diff --git a/convex_decomposition/Makefile b/convex_decomposition/Makefile new file mode 100644 index 0000000..076c2eb --- /dev/null +++ b/convex_decomposition/Makefile @@ -0,0 +1,33 @@ +all: installed + +TARBALL = build/ConvexDecomposition.zip +TARBALL_URL = http://pr.willowgarage.com/downloads/ConvexDecomposition.zip +SOURCE_DIR = build/convex_decomposition +INITIAL_DIR = build/ConvexDecomposition +UNPACK_CMD = unzip +TARBALL_PATCH=convex_decomposition.patch + +include $(shell rospack find mk)/download_unpack_build.mk + +ROOT = $(shell rospack find convex_decomposition)/convex_decomposition + +installed: wiped $(SOURCE_DIR)/unpacked + @echo "making it" + @echo "ROOT is: $(ROOT)" + -mkdir -p $(ROOT) + -mkdir -p $(ROOT)/bin + cd $(SOURCE_DIR) ; make $(ROS_PARALLEL_JOBS); make install + touch installed + +wiped: Makefile + make wipe + touch wiped + +clean: + -cd $(SOURCE_DIR) && make clean + rm -rf $(ROOT) installed + +wipe: clean + rm -rf build + +.PHONY : clean download wipe diff --git a/convex_decomposition/convex_decomposition.patch b/convex_decomposition/convex_decomposition.patch new file mode 100644 index 0000000..db8d786 --- /dev/null +++ b/convex_decomposition/convex_decomposition.patch @@ -0,0 +1,429 @@ +Index: ConvexDecomposition/vlookup.cpp +=================================================================== +--- ConvexDecomposition/vlookup.cpp (revision 8299) ++++ ConvexDecomposition/vlookup.cpp (working copy) +@@ -164,7 +164,7 @@ + }; + + +-template class VertexLess ++template class VertexLess + { + public: + typedef std::vector< Type > VertexVector; +@@ -188,7 +188,7 @@ + static VertexVector *mList; + }; + +-template class VertexPool ++template class VertexPool + { + public: + typedef std::set > VertexSet; +@@ -197,7 +197,7 @@ + int GetVertex(const Type& vtx) + { + VertexLess::SetSearch(vtx,&mVtxs); +- VertexSet::iterator found; ++ typename VertexSet::iterator found; + found = mVertSet.find( -1 ); + if ( found != mVertSet.end() ) + { +@@ -254,10 +254,10 @@ + VertexVector mVtxs; // set of vertices. + }; + ++double tmpp[3] = {0,0,0}; ++template<> VertexPosition VertexLess::mFind = tmpp; ++template<> std::vector *VertexLess::mList =0; + +-VertexPosition VertexLess::mFind; +-std::vector *VertexLess::mList=0; +- + enum RDIFF + { + RD_EQUAL, +@@ -288,6 +288,7 @@ + } + + ++template<> + bool VertexLess::operator()(int v1,int v2) const + { + bool ret = false; +Index: ConvexDecomposition/ConvexDecomposition.cpp +=================================================================== +--- ConvexDecomposition/ConvexDecomposition.cpp (revision 8299) ++++ ConvexDecomposition/ConvexDecomposition.cpp (working copy) +@@ -66,7 +66,7 @@ + #include "cd_vector.h" + #include "cd_hull.h" + #include "bestfit.h" +-#include "PlaneTri.h" ++#include "planetri.h" + #include "vlookup.h" + #include "splitplane.h" + #include "meshvolume.h" +@@ -760,3 +760,3 @@ +- assert( fcount >= 3 && fcount <= 4); +- assert( bcount >= 3 && bcount <= 4); +- ++ if ( fcount >= 3 && fcount <= 4) ++ if ( bcount >= 3 && bcount <= 4) ++ { +@@ -777,1 +777,1 @@ +- ++ } +Index: ConvexDecomposition/splitplane.cpp +=================================================================== +--- ConvexDecomposition/splitplane.cpp (revision 8299) ++++ ConvexDecomposition/splitplane.cpp (working copy) +@@ -67,7 +67,7 @@ + #include "cd_hull.h" + #include "cd_wavefront.h" + #include "bestfit.h" +-#include "PlaneTri.h" ++#include "planetri.h" + #include "vlookup.h" + #include "meshvolume.h" + #include "bestfitobb.h" +Index: ConvexDecomposition/cd_vector.h +=================================================================== +--- ConvexDecomposition/cd_vector.h (revision 8299) ++++ ConvexDecomposition/cd_vector.h (working copy) +@@ -309,12 +309,12 @@ + + Type FastMagnitude(void) const + { +- return Type(fast_sqrt(x * x + y * y + z * z)); ++ return Type(sqrt(x * x + y * y + z * z)); + }; + + Type FasterMagnitude(void) const + { +- return Type(faster_sqrt(x * x + y * y + z * z)); ++ return Type(sqrt(x * x + y * y + z * z)); + }; + + void Lerp(const Vector3d& from,const Vector3d& to,double slerp) +@@ -436,13 +436,13 @@ + + Type FastLength(void) const // length of vector. + { +- return Type(fast_sqrt( x*x + y*y + z*z )); ++ return Type(sqrt( x*x + y*y + z*z )); + }; + + + Type FasterLength(void) const // length of vector. + { +- return Type(faster_sqrt( x*x + y*y + z*z )); ++ return Type(sqrt( x*x + y*y + z*z )); + }; + + Type Length2(void) const // squared distance, prior to square root. +@@ -518,7 +518,7 @@ + + inline double FastNormalize(void) // normalize to a unit vector, returns distance. + { +- double d = fast_sqrt( static_cast< double >( x*x + y*y + z*z ) ); ++ double d = sqrt( static_cast< double >( x*x + y*y + z*z ) ); + if ( d > 0 ) + { + double r = 1.0f / d; +@@ -535,7 +535,7 @@ + + inline double FasterNormalize(void) // normalize to a unit vector, returns distance. + { +- double d = faster_sqrt( static_cast< double >( x*x + y*y + z*z ) ); ++ double d = sqrt( static_cast< double >( x*x + y*y + z*z ) ); + if ( d > 0 ) + { + double r = 1.0f / d; +@@ -1029,7 +1029,8 @@ + + void Zero(void) + { +- x = y = z = 0; ++ x = 0; ++ y = 0; + }; + + Vector2d negative(void) const +@@ -1047,12 +1048,12 @@ + + Type fastmagnitude(void) const + { +- return (Type) fast_sqrt(x * x + y * y ); ++ return (Type) sqrt(x * x + y * y ); + } + + Type fastermagnitude(void) const + { +- return (Type) faster_sqrt( x * x + y * y ); ++ return (Type) sqrt( x * x + y * y ); + } + + void Reflection(Vector2d &a,Vector2d &b); // compute reflection vector. +@@ -1064,12 +1065,12 @@ + + Type FastLength(void) const // length of vector. + { +- return Type(fast_sqrt( x*x + y*y )); ++ return Type(sqrt( x*x + y*y )); + }; + + Type FasterLength(void) const // length of vector. + { +- return Type(faster_sqrt( x*x + y*y )); ++ return Type(sqrt( x*x + y*y )); + }; + + Type Length2(void) // squared distance, prior to square root. +@@ -1090,7 +1091,7 @@ + Type dx = a.x - x; + Type dy = a.y - y; + Type d = dx*dx+dy*dy; +- return fast_sqrt(d); ++ return sqrt(d); + }; + + Type FasterDistance(const Vector2d &a) const // distance between two points. +@@ -1098,7 +1099,7 @@ + Type dx = a.x - x; + Type dy = a.y - y; + Type d = dx*dx+dy*dy; +- return faster_sqrt(d); ++ return sqrt(d); + }; + + Type Distance2(Vector2d &a) // squared distance. +Index: ConvexDecomposition/float_math.cpp +=================================================================== +--- ConvexDecomposition/float_math.cpp (revision 8299) ++++ ConvexDecomposition/float_math.cpp (working copy) +@@ -212,8 +212,14 @@ + matrix[1*4+2] = 2 * ( yz + wx ); + matrix[2*4+2] = 1 - 2 * ( xx + yy ); + +- matrix[3*4+0] =(double) matrix[3*4+1] = matrix[3*4+2] = 0.0f; +- matrix[0*4+3] =(double) matrix[1*4+3] = matrix[2*4+3] = 0.0f; ++ matrix[3*4+0] = 0.0f; ++ matrix[3*4+1] = 0.0f; ++ matrix[3*4+2] = 0.0f; ++ ++ matrix[0*4+3] = 0.0f; ++ matrix[1*4+3] = 0.0f; ++ matrix[2*4+3] = 0.0f; ++ + matrix[3*4+3] =(double) 1.0f; + + } +Index: ConvexDecomposition/cd_wavefront.cpp +=================================================================== +--- ConvexDecomposition/cd_wavefront.cpp (revision 8299) ++++ ConvexDecomposition/cd_wavefront.cpp (working copy) +@@ -672,7 +672,7 @@ + const char *foo = argv[0]; + if ( *foo != '#' ) + { +- if ( stricmp(argv[0],"v") == 0 && argc == 4 ) ++ if ( strcmp(argv[0],"v") == 0 && argc == 4 ) + { + double vx = (double) atof( argv[1] ); + double vy = (double) atof( argv[2] ); +@@ -681,14 +681,14 @@ + mVerts.push_back(vy); + mVerts.push_back(vz); + } +- else if ( stricmp(argv[0],"vt") == 0 && argc == 3 ) ++ else if ( strcmp(argv[0],"vt") == 0 && argc == 3 ) + { + double tx = (double) atof( argv[1] ); + double ty = (double) atof( argv[2] ); + mTexels.push_back(tx); + mTexels.push_back(ty); + } +- else if ( stricmp(argv[0],"vn") == 0 && argc == 4 ) ++ else if ( strcmp(argv[0],"vn") == 0 && argc == 4 ) + { + double normalx = (double) atof(argv[1]); + double normaly = (double) atof(argv[2]); +@@ -697,7 +697,7 @@ + mNormals.push_back(normaly); + mNormals.push_back(normalz); + } +- else if ( stricmp(argv[0],"f") == 0 && argc >= 4 ) ++ else if ( strcmp(argv[0],"f") == 0 && argc >= 4 ) + { + GeometryVertex v[32]; + +Index: Makefile +=================================================================== +--- Makefile (revision 0) ++++ Makefile (revision 8581) +@@ -0,0 +1,93 @@ ++ ++ ++OBJS = DecomposeSample.o \ ++ ConvexDecomposition/bestfit.o ConvexDecomposition/float_math.o \ ++ ConvexDecomposition/bestfitobb.o ConvexDecomposition/meshvolume.o \ ++ ConvexDecomposition/cd_hull.o ConvexDecomposition/planetri.o \ ++ ConvexDecomposition/cd_wavefront.o ConvexDecomposition/raytri.o \ ++ ConvexDecomposition/concavity.o ConvexDecomposition/splitplane.o \ ++ ConvexDecomposition/ConvexDecomposition.o ConvexDecomposition/triangulate.o \ ++ ConvexDecomposition/fitsphere.o ConvexDecomposition/vlookup.o ++ ++HEADERS = \ ++ ConvexDecomposition/bestfit.h \ ++ ConvexDecomposition/bestfitobb.h \ ++ ConvexDecomposition/cd_hull.h \ ++ ConvexDecomposition/cd_vector.h \ ++ ConvexDecomposition/cd_wavefront.h \ ++ ConvexDecomposition/concavity.h \ ++ ConvexDecomposition/ConvexDecomposition.h \ ++ ConvexDecomposition/fitsphere.h \ ++ ConvexDecomposition/float_math.h \ ++ ConvexDecomposition/meshvolume.h \ ++ ConvexDecomposition/planetri.h \ ++ ConvexDecomposition/raytri.h \ ++ ConvexDecomposition/splitplane.h \ ++ ConvexDecomposition/triangulate.h \ ++ ConvexDecomposition/vlookup.h ++ ++CC = g++ ++ ++DEBUG = -ggdb ++ ++CFLAGS = -IConvexDecomposition -Wall -c $(DEBUG) ++ ++LFLAGS = $(DEBUG) ++ ++convex_decomposition: $(OBJS) ++ $(CC) $(LFLAGS) $(OBJS) -o convex_decomposition ++ ++DecomposeSample.o: DecomposeSample.cpp ++ $(CC) $(CFLAGS) DecomposeSample.cpp -o $@ ++ ++ConvexDecomposition/bestfit.o: ConvexDecomposition/bestfit.cpp ++ $(CC) $(CFLAGS) ConvexDecomposition/bestfit.cpp -o $@ ++ ++ConvexDecomposition/bestfitobb.o: ConvexDecomposition/bestfitobb.cpp ++ $(CC) $(CFLAGS) ConvexDecomposition/bestfitobb.cpp -o $@ ++ ++ConvexDecomposition/cd_hull.o: ConvexDecomposition/cd_hull.cpp ++ $(CC) $(CFLAGS) ConvexDecomposition/cd_hull.cpp -o $@ ++ ++ConvexDecomposition/cd_wavefront.o: ConvexDecomposition/cd_wavefront.cpp ++ $(CC) $(CFLAGS) ConvexDecomposition/cd_wavefront.cpp -o $@ ++ ++ConvexDecomposition/concavity.o: ConvexDecomposition/concavity.cpp ++ $(CC) $(CFLAGS) ConvexDecomposition/concavity.cpp -o $@ ++ ++ConvexDecomposition/ConvexDecomposition.o: ConvexDecomposition/ConvexDecomposition.cpp ++ $(CC) $(CFLAGS) ConvexDecomposition/ConvexDecomposition.cpp -o $@ ++ ++ConvexDecomposition/fitsphere.o: ConvexDecomposition/fitsphere.cpp ++ $(CC) $(CFLAGS) ConvexDecomposition/fitsphere.cpp -o $@ ++ ++ConvexDecomposition/float_math.o: ConvexDecomposition/float_math.cpp ++ $(CC) $(CFLAGS) ConvexDecomposition/float_math.cpp -o $@ ++ ++ConvexDecomposition/meshvolume.o: ConvexDecomposition/meshvolume.cpp ++ $(CC) $(CFLAGS) ConvexDecomposition/meshvolume.cpp -o $@ ++ ++ConvexDecomposition/planetri.o: ConvexDecomposition/planetri.cpp ++ $(CC) $(CFLAGS) ConvexDecomposition/planetri.cpp -o $@ ++ ++ConvexDecomposition/raytri.o: ConvexDecomposition/raytri.cpp ++ $(CC) $(CFLAGS) ConvexDecomposition/raytri.cpp -o $@ ++ ++ConvexDecomposition/splitplane.o: ConvexDecomposition/splitplane.cpp ++ $(CC) $(CFLAGS) ConvexDecomposition/splitplane.cpp -o $@ ++ ++ConvexDecomposition/triangulate.o: ConvexDecomposition/triangulate.cpp ++ $(CC) $(CFLAGS) ConvexDecomposition/triangulate.cpp -o $@ ++ ++ConvexDecomposition/vlookup.o: ConvexDecomposition/vlookup.cpp ConvexDecomposition/vlookup.cpp ++ $(CC) $(CFLAGS) ConvexDecomposition/vlookup.cpp -o $@ ++ ++install: ++ cp convex_decomposition ../../convex_decomposition/bin/ ++ ++clean: ++ \rm *.o */*.o convex_decomposition ++ ++tar: ++ tar cfv ConvexDecomposition.tar DecomposeSample.cpp convex_decomposition Makefile \ ++ ConvexDecomposition +Index: DecomposeSample.cpp +=================================================================== +--- DecomposeSample.cpp (revision 8299) ++++ DecomposeSample.cpp (working copy) +@@ -6,7 +6,7 @@ + + #include + +-#include "./ConvexDecomposition/convexdecomposition.h" ++#include "./ConvexDecomposition/ConvexDecomposition.h" + #include "./ConvexDecomposition/cd_wavefront.h" + + using namespace ConvexDecomposition; +@@ -227,7 +227,7 @@ + + if ( fph ) + { +- printf("Saving convex decomposition of %d hulls to COLLADA file '%s'\r\n", mHulls.size(), scratch ); ++ printf("Saving convex decomposition of %d hulls to COLLADA file '%s'\r\n", (int)mHulls.size(), scratch ); + + fprintf(fph,"\r\n"); + fprintf(fph,"\r\n"); +@@ -537,7 +537,7 @@ + }; + + +-void main(int argc,const char **argv) ++int main(int argc,const char **argv) + { + if ( argc < 2 ) + { +Index: DecomposeSample.cpp +=================================================================== +--- DecomposeSample.cpp (revision 8299) ++++ DecomposeSample.cpp (working copy) +@@ -67,3 +67,3 @@ + strcpy(mBaseName,fname); +- char *dot = strstr(mBaseName,"."); ++ char *dot = strstr(mBaseName,".obj"); + if ( dot ) *dot = 0; +Index: ConvexDecomposition/cd_wavefront.cpp +=================================================================== +--- ConvexDecomposition/cd_wavefront.cpp (revision 8299) ++++ ConvexDecomposition/cd_wavefront.cpp (working copy) +@@ -573,6 +573,7 @@ + FloatVector mNormals; + + GeometryInterface *mCallback; ++ friend class WavefrontObj; + }; + + +@@ -839,7 +840,17 @@ + memcpy(mIndices, &indices[0], sizeof(int)*mTriCount*3); + ret = mTriCount; + } +- ++ else if( obj.mVerts.size() > 0 ) { ++ // take consecutive vertices ++ mVertexCount = obj.mVerts.size()/3; ++ mVertices = new double[mVertexCount*3]; ++ memcpy( mVertices, &obj.mVerts[0], sizeof(double)*mVertexCount*3 ); ++ mTriCount = mVertexCount/3; ++ mIndices = new int[mTriCount*3*sizeof(int)]; ++ for(int i = 0; i < mVertexCount; ++i) ++ mIndices[i] = i; ++ ret = mTriCount; ++ } + + return ret; + } diff --git a/convex_decomposition/manifest.xml b/convex_decomposition/manifest.xml new file mode 100644 index 0000000..b061753 --- /dev/null +++ b/convex_decomposition/manifest.xml @@ -0,0 +1,14 @@ + + + +Convex Mesh Generation Library + + +John Ratcliff +MIT + +http://www.amillionpixels.us/ConvexDecomposition.zip + + + + diff --git a/ivcon/CMakeLists.txt b/ivcon/CMakeLists.txt new file mode 100644 index 0000000..8169c5a --- /dev/null +++ b/ivcon/CMakeLists.txt @@ -0,0 +1,9 @@ +cmake_minimum_required(VERSION 2.4.6) +include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) +rospack(ivcon) + +#uncomment for profiling +set(ROS_LINK_FLAGS "-lm" ${ROS_LINK_FLAGS}) + +rospack_add_executable(bin/ivcon src/ivcon.c) + diff --git a/ivcon/Makefile b/ivcon/Makefile new file mode 100644 index 0000000..bbd3fc6 --- /dev/null +++ b/ivcon/Makefile @@ -0,0 +1 @@ +include $(shell rospack find mk)/cmake.mk diff --git a/ivcon/manifest.xml b/ivcon/manifest.xml new file mode 100644 index 0000000..2f770e0 --- /dev/null +++ b/ivcon/manifest.xml @@ -0,0 +1,14 @@ + + + +Mesh Conversion Utility + + +John Burkardt +GPL + +https://sourceforge.net/projects/ivcon/ + + + + diff --git a/ivcon/src/ivcon.c b/ivcon/src/ivcon.c new file mode 100644 index 0000000..5539860 --- /dev/null +++ b/ivcon/src/ivcon.c @@ -0,0 +1,16707 @@ +/* ivcon.c 24 May 2001 */ + +/* + Purpose: + + IVCON converts various 3D graphics files. + + Acknowledgements: + + Coding, comments, and advice were supplied by a number of collaborators. + + John F Flanagan made some corrections to the 3D Studio Max routines. + + Zik Saleeba (zik@zikzak.net) enhanced the DXF routines, and added the + Golgotha GMOD routines. + + Thanks to Susan M. Fisher, University of North Carolina, + Department of Computer Science, for pointing out a coding error + in FACE_NULL_DELETE that was overwriting all the data! + + Modified: + + 04 July 2000 + + Author: + + John Burkardt +*/ + +#include +#include +#include +#include +#include + +#define FALSE 0 +#define TRUE 1 + +#define ERROR 1 +#define G1_SECTION_MODEL_QUADS 18 +#define G1_SECTION_MODEL_TEXTURE_NAMES 19 +#define G1_SECTION_MODEL_VERT_ANIMATION 20 +#define GMOD_MAX_SECTIONS 32 +#define GMOD_UNUSED_VERTEX 65535 +#define PI 3.141592653589793238462643 +#define SUCCESS 0 + +#define DEG_TO_RAD ( PI / 180.0 ) +#define RAD_TO_DEG ( 180.0 / PI ) + +/******************************************************************************/ + +/* GLOBAL DATA */ + +/******************************************************************************/ + +/* + BACKGROUND_RGB[3], the background color. + + BYTE_SWAP, byte swapping option. + + COR3[3][COR3_MAX], the coordinates of nodes. + + COR3_MATERIAL[COR3_MAX], the index of the material of each node. + + COR3_MAX, the maximum number of points. + + COR3_NORMAL[3][COR3_MAX], normal vectors associated with nodes. + + COR3_NUM, the number of points. + + COR3_RGB[3][COR3_MAX], RGB colors associated with nodes. + + COR3_TEX_UV[2][COR3_MAX], texture coordinates associated with nodes. + + FACE[ORDER_MAX][FACE_MAX] contains the index of the I-th node making up face J. + + FACE_AREA(FACE_MAX), the area of each face. + + FACE_MATERIAL[FACE_MAX]; the material of each face. + + FACE_MAX, the maximum number of faces. + + FACE_NORMAL[3][FACE_MAX], the face normal vectors. + + FACE_NUM, the number of faces. + + FACE_ORDER[FACE_MAX], the number of vertices per face. + + FACE_TEX_UV[2][FACE_MAX], texture coordinates associated with faces. + + LINE_DEX[LINES_MAX], node indices, denoting polylines, each terminated by -1. + + LINE_MATERIAL[LINES_MAX], index into RGBCOLOR for line color. + + LINES_MAX, the maximum number of line definition items. + + LINE_NUM, the number of line definition items. + + LINE_PRUNE, pruning option ( 0 = no pruning, nonzero = pruning). + + MATERIAL_MAX, the maximum number of materials. + + MATERIAL_NUM, the number of materials. + + ORDER_MAX, the maximum number of vertices per face. + + TEXTURE_MAX, the maximum number of textures. + + TEXTURE_NAME[TEXTURE_MAX][LINE_MAX_LEN], ... + + TEXTURE_NUM, the number of textures. + + TRANSFORM_MATRIX[4][4], the current transformation matrix. + + VERTEX_MATERIAL[ORDER_MAX][FACE_MAX]; the material of vertices of faces. + + VERTEX_NORMAL[3][ORDER_MAX][FACE_MAX], normals at vertices of faces. + + VERTEX_RGB[3][ORDER_MAX][FACE_MAX], colors of vertices of faces. + + VERTEX_TEX_UV[2][ORDER_MAX][FACE_MAX], texture coordinates of vertices of faces. +*/ + +#define COLOR_MAX 1000 +#define COR3_MAX 200000 +#define FACE_MAX 200000 +#define LINE_MAX_LEN 256 +#define LEVEL_MAX 10 +#define LINES_MAX 100000 +#define MATERIAL_MAX 100 +#define ORDER_MAX 10 +#define TEXTURE_MAX 100 + +char anim_name[LINE_MAX_LEN]; +float background_rgb[3]; +int bad_num; +int byte_swap; +int bytes_num; +int color_num; +int comment_num; + +float cor3[3][COR3_MAX]; +int cor3_material[COR3_MAX]; +float cor3_normal[3][COR3_MAX]; +int cor3_num; +float cor3_tex_uv[3][COR3_MAX]; + +int debug; + +int dup_num; + +int face[ORDER_MAX][FACE_MAX]; +float face_area[FACE_MAX]; +int face_flags[FACE_MAX]; +int face_material[FACE_MAX]; +float face_normal[3][FACE_MAX]; +int face_num; +int face_object[FACE_MAX]; +int face_order[FACE_MAX]; +int face_smooth[FACE_MAX]; +float face_tex_uv[2][FACE_MAX]; + +char filein_name[1024]; +char fileout_name[1024]; + +int group_num; + +int i; +char input[LINE_MAX_LEN]; +int k; +char level_name[LEVEL_MAX][LINE_MAX_LEN]; + +int line_dex[LINES_MAX]; +int line_material[LINES_MAX]; +int line_num; +int line_prune; + +int list[COR3_MAX]; + +char material_binding[80]; +char material_name[MATERIAL_MAX][LINE_MAX_LEN]; +int material_num; +float material_rgba[4][MATERIAL_MAX]; + +char mat_name[81]; +int max_order2; + +char normal_binding[80]; +float normal_temp[3][ORDER_MAX*FACE_MAX]; + +char object_name[81]; +int object_num; + +float origin[3]; +float pivot[3]; +float rgbcolor[3][COLOR_MAX]; +char temp_name[81]; + +int text_num; + +char texture_binding[80]; +char texture_name[TEXTURE_MAX][LINE_MAX_LEN]; +int texture_num; +float texture_temp[2][ORDER_MAX*FACE_MAX]; + +float transform_matrix[4][4]; + +int vertex_material[ORDER_MAX][FACE_MAX]; +float vertex_normal[3][ORDER_MAX][FACE_MAX]; +float vertex_rgb[3][ORDER_MAX][FACE_MAX]; +float vertex_tex_uv[2][ORDER_MAX][FACE_MAX]; + +/******************************************************************************/ + +/* FUNCTION PROTOTYPES */ + +/******************************************************************************/ + +int main ( int argc, char **argv ); +int ase_read ( FILE *filein ); +int ase_write ( FILE *fileout ); +int byu_read ( FILE *filein ); +int byu_write ( FILE *fileout ); +int char_index_last ( char* string, char c ); +int char_pad ( int *char_index, int *null_index, char *string, + int STRING_MAX ); +char char_read ( FILE *filein ); +int char_write ( FILE *fileout, char c ); +int command_line ( char **argv ); +void cor3_normal_set ( void ); +void cor3_range ( void ); +void data_check ( void ); +void data_init ( void ); +int data_read ( void ); +void data_report ( void ); +int data_write ( void ); +int dxf_read ( FILE *filein ); +int dxf_write ( FILE *fileout ); +void edge_null_delete ( void ); +void face_area_set ( void ); +void face_normal_ave ( void ); +void face_null_delete ( void ); +int face_print ( int iface ); +void face_reverse_order ( void ); +int face_subset ( void ); +void face_to_line ( void ); +void face_to_vertex_material ( void ); +char *file_ext ( char *file_name ); +float float_read ( FILE *filein ); +float float_reverse_bytes ( float x ); +int float_write ( FILE *fileout, float float_val ); +int gmod_arch_check ( void ); +int gmod_read ( FILE *filein ); +float gmod_read_float ( FILE *filein ); +unsigned short gmod_read_w16 ( FILE *filein ); +unsigned long gmod_read_w32 ( FILE *filein ); +int gmod_write ( FILE *fileout ); +void gmod_write_float ( float Val, FILE *fileout ); +void gmod_write_w16 ( unsigned short Val, FILE *fileout ); +void gmod_write_w32 ( unsigned long Val, FILE *fileout ); +void hello ( void ); +void help ( void ); +int hrc_read ( FILE *filein ); +int hrc_write ( FILE *fileout ); +void init_program_data ( void ); +int interact ( void ); +int iv_read ( FILE *filein ); +int iv_write ( FILE *fileout ); +int ivec_max ( int n, int *a ); +int leqi ( char* string1, char* string2 ); +long int long_int_read ( FILE *filein ); +int long_int_write ( FILE *fileout, long int int_val ); +void news ( void ); +void node_to_vertex_material ( void ); +int obj_read ( FILE *filein ); +int obj_write ( FILE *fileout ); +int pov_write ( FILE *fileout ); +int rcol_find ( float a[][COR3_MAX], int m, int n, float r[] ); +float rgb_to_hue ( float r, float g, float b ); +short int short_int_read ( FILE *filein ); +int short_int_write ( FILE *fileout, short int int_val ); +int smf_read ( FILE *filein ); +int smf_write ( FILE *fileout ); +int stla_read ( FILE *filein ); +int stla_write ( FILE *fileout ); +int stlb_read ( FILE *filein ); +int stlb_write ( FILE *fileout ); +void tds_pre_process ( void ); +int tds_read ( FILE *filein ); +unsigned long int tds_read_ambient_section ( FILE *filein ); +unsigned long int tds_read_background_section ( FILE *filein ); +unsigned long int tds_read_boolean ( unsigned char *boolean, FILE *filein ); +unsigned long int tds_read_camera_section ( FILE *filein ); +unsigned long int tds_read_edit_section ( FILE *filein, int *views_read ); +unsigned long int tds_read_keyframe_section ( FILE *filein, int *views_read ); +unsigned long int tds_read_keyframe_objdes_section ( FILE *filein ); +unsigned long int tds_read_light_section ( FILE *filein ); +unsigned long int tds_read_u_long_int ( FILE *filein ); +int tds_read_long_name ( FILE *filein ); +unsigned long int tds_read_matdef_section ( FILE *filein ); +unsigned long int tds_read_material_section ( FILE *filein ); +int tds_read_name ( FILE *filein ); +unsigned long int tds_read_obj_section ( FILE *filein ); +unsigned long int tds_read_object_section ( FILE *filein ); +unsigned long int tds_read_tex_verts_section ( FILE *filein ); +unsigned long int tds_read_texmap_section ( FILE *filein ); +unsigned short int tds_read_u_short_int ( FILE *filein ); +unsigned long int tds_read_spot_section ( FILE *filein ); +unsigned long int tds_read_unknown_section ( FILE *filein ); +unsigned long int tds_read_view_section ( FILE *filein, int *views_read ); +unsigned long int tds_read_vp_section ( FILE *filein, int *views_read ); +int tds_write ( FILE *fileout ); +int tds_write_string ( FILE *fileout, char *string ); +int tds_write_u_short_int ( FILE *fileout, + unsigned short int int_val ); +int tec_write ( FILE *fileout ); +void tmat_init ( float a[4][4] ); +void tmat_mxm ( float a[4][4], float b[4][4], float c[4][4] ); +void tmat_mxp ( float a[4][4], float x[4], float y[4] ); +void tmat_mxp2 ( float a[4][4], float x[][3], float y[][3], int n ); +void tmat_mxv ( float a[4][4], float x[4], float y[4] ); +void tmat_rot_axis ( float a[4][4], float b[4][4], float angle, + char axis ); +void tmat_rot_vector ( float a[4][4], float b[4][4], float angle, + float v1, float v2, float v3 ); +void tmat_scale ( float a[4][4], float b[4][4], float sx, float sy, + float sz ); +void tmat_shear ( float a[4][4], float b[4][4], char *axis, + float s ); +void tmat_trans ( float a[4][4], float b[4][4], float x, float y, + float z ); +int tria_read ( FILE *filein ); +int tria_write ( FILE *fileout ); +int trib_read ( FILE *filein ); +int trib_write ( FILE *fileout ); +int txt_write ( FILE *fileout ); +int ucd_write ( FILE *fileout ); +void vertex_normal_set ( void ); +void vertex_to_face_material ( void ); +void vertex_to_node_material ( void ); +int vla_read ( FILE *filein ); +int vla_write ( FILE *fileout ); +int wrl_write ( FILE *filout ); +int xgl_write ( FILE *fileout ); + +/******************************************************************************/ + +int main ( int argc, char **argv ) + +/******************************************************************************/ + +/* + Purpose: + + MAIN is the main program for converting graphics files. + + Modified: + + 26 May 1999 + + Author: + + John Burkardt +*/ +{ + int result; +/* + Initialize the program data. +*/ + init_program_data ( ); +/* + If there are at least two command line arguments, call COMMAND_LINE. + Otherwise call INTERACT and get information from the user. +*/ + if ( argc >= 2 ) { + result = command_line ( argv ); + } + else { + result = interact ( ); + } + + return result; +} +/******************************************************************************/ + +int ase_read ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + ASE_READ reads an AutoCAD ASE file. + + Modified: + + 22 May 1999 + + Author: + + John Burkardt +*/ +{ + float bval; + int count; + float gval; + int i; + int iface; + int ivert; + int iword; + int level; + char *next; + int nlbrack; + int nrbrack; + int cor3_num_old; + int face_num_old; + float rval; + float temp; + int width; + char word[LINE_MAX_LEN]; + char word1[LINE_MAX_LEN]; + char word2[LINE_MAX_LEN]; + char wordm1[LINE_MAX_LEN]; + float x; + float y; + float z; + + level = 0; + strcpy ( level_name[0], "Top" ); + cor3_num_old = cor3_num; + face_num_old = face_num; + nlbrack = 0; + nrbrack = 0; + + strcpy ( word, " " ); + strcpy ( wordm1, " " ); +/* + Read a line of text from the file. +*/ + + for ( ;; ) { + + if ( fgets ( input, LINE_MAX_LEN, filein ) == NULL ) { + break; + } + + text_num = text_num + 1; + next = input; + iword = 0; +/* + Read the next word from the line. +*/ + for ( ;; ) { + + strcpy ( wordm1, word ); + strcpy ( word, " " ); + + count = sscanf ( next, "%s%n", word, &width ); + next = next + width; + + if ( count <= 0 ) { + break; + } + + iword = iword + 1; + + if ( iword == 1 ) { + strcpy ( word1, word ); + } +/* + In case the new word is a bracket, update the bracket count. +*/ + if ( strcmp ( word, "{" ) == 0 ) { + + nlbrack = nlbrack + 1; + level = nlbrack - nrbrack; + strcpy ( level_name[level], wordm1 ); + } + else if ( strcmp ( word, "}" ) == 0 ) { + + nrbrack = nrbrack + 1; + + if ( nlbrack < nrbrack ) { + + printf ( "\n" ); + printf ( "ASE_READ - Fatal error!\n" ); + printf ( " Extraneous right bracket on line %d\n", text_num ); + printf ( " Currently processing field:\n" ); + printf ( "%s\n", level_name[level] ); + return ERROR; + } + + } +/* + *3DSMAX_ASCIIEXPORT 200 +*/ + if ( strcmp ( word1, "*3DSMAX_ASCIIEXPORT" ) == 0 ) { + break; + } +/* + *COMMENT +*/ + else if ( strcmp ( word1, "*COMMENT" ) == 0 ) { + break; + } +/* + *GEOMOBJECT +*/ + else if ( strcmp ( level_name[level], "*GEOMOBJECT" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + continue; + } +/* + Why don't you read and save this name? +*/ + else if ( strcmp ( word, "*NODE_NAME" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*NODE_TM" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "*MESH" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "*PROP_CASTSHADOW" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*PROP_MOTIONBLUR" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*PROP_RECVSHADOW" ) == 0 ) { + break; + } + else { + bad_num = bad_num + 1; + printf ( "Bad data in GEOMOBJECT, line %d\n", text_num ); + break; + } + } +/* + *MESH +*/ + else if ( strcmp ( level_name[level], "*MESH" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + continue; + } + else if ( strcmp ( word, "*MESH_CFACELIST" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "*MESH_CVERTLIST" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "*MESH_FACE_LIST" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "*MESH_NORMALS" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "*MESH_NUMCVERTEX" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*MESH_NUMCVFACES" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*MESH_NUMFACES" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*MESH_NUMTVERTEX" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*MESH_NUMTVFACES" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*MESH_NUMVERTEX" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*MESH_TFACELIST" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "*MESH_TVERTLIST" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "*MESH_VERTEX_LIST" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "*TIMEVALUE" ) == 0 ) { + break; + } + else { + bad_num = bad_num + 1; + printf ( "Bad data in MESH, line %d\n", text_num ); + break; + } + } +/* + *MESH_CFACELIST +*/ + else if ( strcmp ( level_name[level], "*MESH_CFACELIST" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + continue; + } + else if ( strcmp ( word, "*MESH_CFACE" ) == 0 ) { + break; + } + else { + bad_num = bad_num + 1; + printf ( "Bad data in MESH_CFACE, line %d\n", text_num ); + break; + } + } +/* + *MESH_CVERTLIST + + Mesh vertex indices must be incremented by COR3_NUM_OLD before being stored + in the internal array. +*/ + else if ( strcmp ( level_name[level], "*MESH_CVERTLIST" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + continue; + } + else if ( strcmp ( word, "*MESH_VERTCOL" ) == 0 ) { + + count = sscanf ( next, "%d%n", &i, &width ); + next = next + width; + + i = i + cor3_num_old; + + count = sscanf ( next, "%f%n", &rval, &width ); + next = next + width; + + count = sscanf ( next, "%f%n", &gval, &width ); + next = next + width; + + count = sscanf ( next, "%f%n", &bval, &width ); + next = next + width; + + if ( material_num < MATERIAL_MAX ) { + material_rgba[0][material_num] = rval; + material_rgba[1][material_num] = gval; + material_rgba[2][material_num] = bval; + material_rgba[3][material_num] = 1.0; + } + + material_num = material_num + 1; + cor3_material[i] = material_num; + } + else { + bad_num = bad_num + 1; + printf ( "\n" ); + printf ( "ASE_READ - Warning!\n" ); + printf ( " Bad data in MESH_CVERTLIST, line %d\n", text_num ); + break; + } + + } +/* + *MESH_FACE_LIST + This coding assumes a face is always triangular or quadrilateral. +*/ + else if ( strcmp ( level_name[level], "*MESH_FACE_LIST" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + continue; + } + else if ( strcmp ( word, "*MESH_FACE" ) == 0 ) { + + if ( face_num < FACE_MAX ) { + + face_material[face_num] = 0; + face_order[face_num] = 0; + + count = sscanf ( next, "%d%n", &i, &width ); + next = next + width; + + count = sscanf ( next, "%s%n", word2, &width ); + next = next + width; + count = sscanf ( next, "%s%n", word2, &width ); + next = next + width; + + count = sscanf ( next, "%d%n", &i, &width ); + next = next + width; + face[0][face_num] = i + cor3_num_old; + face_order[face_num] = face_order[face_num] + 1; + + count = sscanf ( next, "%s%n", word2, &width ); + next = next + width; + + count = sscanf ( next, "%d%n", &i, &width ); + next = next + width; + face[1][face_num] = i + cor3_num_old; + face_order[face_num] = face_order[face_num] + 1; + + count = sscanf ( next, "%s%n", word2, &width ); + next = next + width; + + count = sscanf ( next, "%d%n", &i, &width ); + next = next + width; + face[2][face_num] = i + cor3_num_old; + face_order[face_num] = face_order[face_num] + 1; + + count = sscanf ( next, "%s%n", word2, &width ); + next = next + width; + + if ( strcmp ( word2, "D:" ) == 0 ) { + count = sscanf ( next, "%d%n", &i, &width ); + next = next + width; + face[3][face_num] = i + cor3_num_old; + face_order[face_num] = face_order[face_num] + 1; + } + } + + face_num = face_num + 1; + + break; + + } + else { + bad_num = bad_num + 1; + printf ( "Bad data in MESH_FACE_LIST, line %d\n", text_num ); + break; + } + } +/* + *MESH_NORMALS +*/ + else if ( strcmp ( level_name[level], "*MESH_NORMALS" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + continue; + } + else if ( strcmp ( word, "*MESH_FACENORMAL" ) == 0 ) { + + count = sscanf ( next, "%d%n", &iface, &width ); + next = next + width; + + count = sscanf ( next, "%f%n", &x, &width ); + next = next + width; + + count = sscanf ( next, "%f%n", &y, &width ); + next = next + width; + + count = sscanf ( next, "%f%n", &z, &width ); + next = next + width; + + iface = iface + face_num_old; + ivert = 0; + + face_normal[0][iface] = x; + face_normal[1][iface] = y; + face_normal[2][iface] = z; + + break; + + } + else if ( strcmp ( word, "*MESH_VERTEXNORMAL" ) == 0 ) { + + count = sscanf ( next, "%d%n", &i, &width ); + next = next + width; + + count = sscanf ( next, "%f%n", &x, &width ); + next = next + width; + + count = sscanf ( next, "%f%n", &y, &width ); + next = next + width; + + count = sscanf ( next, "%f%n", &z, &width ); + next = next + width; + + vertex_normal[0][ivert][iface] = x; + vertex_normal[1][ivert][iface] = y; + vertex_normal[2][ivert][iface] = z; + ivert = ivert + 1; + + break; + } + else { + bad_num = bad_num + 1; + printf ( "Bad data in MESH_NORMALS, line %d\n", text_num ); + break; + } + } +/* + *MESH_TFACELIST +*/ + else if ( strcmp ( level_name[level], "*MESH_TFACELIST" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + continue; + } + else if ( strcmp ( word1, "*MESH_TFACE" ) == 0 ) { + break; + } + else { + bad_num = bad_num + 1; + printf ( "Bad data in MESH_TFACE_LIST, line %d\n", text_num ); + break; + } + } +/* + *MESH_TVERTLIST +*/ + else if ( strcmp ( level_name[level], "*MESH_TVERTLIST" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + continue; + } + else if ( strcmp ( word1, "*MESH_TVERT" ) == 0 ) { + break; + } + else { + bad_num = bad_num + 1; + printf ( "Bad data in MESH_TVERTLIST, line %d\n", text_num ); + break; + } + } +/* + *MESH_VERTEX_LIST +*/ + else if ( strcmp ( level_name[level], "*MESH_VERTEX_LIST" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + cor3_num_old = cor3_num; + continue; + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + continue; + } + else if ( strcmp ( word1, "*MESH_VERTEX" ) == 0 ) { + + count = sscanf ( next, "%d%n", &i, &width ); + next = next + width; + + count = sscanf ( next, "%f%n", &x, &width ); + next = next + width; + + count = sscanf ( next, "%f%n", &y, &width ); + next = next + width; + + count = sscanf ( next, "%f%n", &z, &width ); + next = next + width; + + i = i + cor3_num_old; + if ( cor3_num < i + 1 ) { + cor3_num = i + 1; + } + + if ( i < COR3_MAX ) { + + cor3[0][i] = + transform_matrix[0][0] * x + + transform_matrix[0][1] * y + + transform_matrix[0][2] * z + + transform_matrix[0][3]; + + cor3[1][i] = + transform_matrix[1][0] * x + + transform_matrix[1][1] * y + + transform_matrix[1][2] * z + + transform_matrix[1][3]; + + cor3[2][i] = + transform_matrix[2][0] * x + + transform_matrix[2][1] * y + + transform_matrix[2][2] * z + + transform_matrix[2][3]; + } + + break; + } + else { + bad_num = bad_num + 1; + printf ( "Bad data in MESH_VERTEX_LIST, line %d\n", text_num ); + break; + } + } +/* + *NODE_TM + + Each node should start out with a default transformation matrix. +*/ + else if ( strcmp ( level_name[level], "*NODE_TM" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + + tmat_init ( transform_matrix ); + + continue; + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + continue; + } + else if ( strcmp ( word, "*INHERIT_POS" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*INHERIT_ROT" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*INHERIT_SCL" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*NODE_NAME" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*TM_POS" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*TM_ROTANGLE" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*TM_ROTAXIS" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*TM_ROW0" ) == 0 ) { + + count = sscanf ( next, "%f%n", &temp, &width ); + next = next + width; + transform_matrix[0][0] = temp; + + count = sscanf ( next, "%f%n", &temp, &width ); + next = next + width; + transform_matrix[1][0] = temp; + + count = sscanf ( next, "%f%n", &temp, &width ); + next = next + width; + transform_matrix[2][0] = temp; + + break; + } + else if ( strcmp ( word, "*TM_ROW1" ) == 0 ) { + + count = sscanf ( next, "%f%n", &temp, &width ); + next = next + width; + transform_matrix[0][1] = temp; + + count = sscanf ( next, "%f%n", &temp, &width ); + next = next + width; + transform_matrix[1][1] = temp; + + count = sscanf ( next, "%f%n", &temp, &width ); + next = next + width; + transform_matrix[2][1] = temp; + + break; + } + else if ( strcmp ( word, "*TM_ROW2" ) == 0 ) { + + count = sscanf ( next, "%f%n", &temp, &width ); + next = next + width; + transform_matrix[0][2] = temp; + + count = sscanf ( next, "%f%n", &temp, &width ); + next = next + width; + transform_matrix[1][2] = temp; + + count = sscanf ( next, "%f%n", &temp, &width ); + next = next + width; + transform_matrix[2][2] = temp; + + break; + } + else if ( strcmp ( word, "*TM_ROW3" ) == 0 ) { + + count = sscanf ( next, "%f%n", &temp, &width ); + next = next + width; + transform_matrix[0][3] = temp; + + count = sscanf ( next, "%f%n", &temp, &width ); + next = next + width; + transform_matrix[1][3] = temp; + + count = sscanf ( next, "%f%n", &temp, &width ); + next = next + width; + transform_matrix[2][3] = temp; + + break; + } + else if ( strcmp ( word, "*TM_SCALE" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*TM_SCALEAXIS" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*TM_SCALEAXISANG" ) == 0 ) { + break; + } + else { + bad_num = bad_num + 1; + printf ( "Bad data in NODE_TM, line %d\n", text_num ); + break; + } + } +/* + *SCENE +*/ + else if ( strcmp ( level_name[level], "*SCENE" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + continue; + } + else if ( strcmp ( word, "*SCENE_AMBIENT_STATIC" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*SCENE_BACKGROUND_STATIC" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*SCENE_FILENAME" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*SCENE_FIRSTFRAME" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*SCENE_FRAMESPEED" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*SCENE_LASTFRAME" ) == 0 ) { + break; + } + else if ( strcmp ( word, "*SCENE_TICKSPERFRAME" ) == 0 ) { + break; + } + else { + bad_num = bad_num + 1; + printf ( "Bad data in SCENE, line %d\n", text_num ); + break; + } + + } + + } +/* + End of loop reading words from the line. +*/ + } +/* + End of loop reading lines from input file. +*/ + + return SUCCESS; +} +/******************************************************************************/ + +int ase_write ( FILE *fileout ) + +/******************************************************************************/ + +/* + Purpose: + + ASE_WRITE writes graphics information to an AutoCAD ASE file. + + Modified: + + 30 September 1998 + + Author: + + John Burkardt + +*/ +{ + int i1; + int i2; + int i3; + int i4; + int iface; + int ivert; + int j; + int text_num; + + text_num = 0; +/* + Write the header. +*/ + fprintf ( fileout, "*3DSMAX_ASCIIEXPORT 200\n" ); + fprintf ( fileout, "*COMMENT \"%s, created by IVCON.\"\n", fileout_name ); + fprintf ( fileout, "*COMMENT \"Original data in %s\"\n", filein_name ); + + text_num = text_num + 3; +/* + Write the scene block. +*/ + fprintf ( fileout, "*SCENE {\n" ); + fprintf ( fileout, " *SCENE_FILENAME \"\"\n" ); + fprintf ( fileout, " *SCENE_FIRSTFRAME 0\n" ); + fprintf ( fileout, " *SCENE_LASTFRAME 100\n" ); + fprintf ( fileout, " *SCENE_FRAMESPEED 30\n" ); + fprintf ( fileout, " *SCENE_TICKSPERFRAME 160\n" ); + fprintf ( fileout, " *SCENE_BACKGROUND_STATIC 0.0000 0.0000 0.0000\n" ); + fprintf ( fileout, " *SCENE_AMBIENT_STATIC 0.0431 0.0431 0.0431\n" ); + fprintf ( fileout, "}\n" ); + + text_num = text_num + 9; +/* + Begin the big geometry block. +*/ + fprintf ( fileout, "*GEOMOBJECT {\n" ); + fprintf ( fileout, " *NODE_NAME \"%s\"\n", object_name ); + + text_num = text_num + 2; +/* + Sub block NODE_TM: +*/ + fprintf ( fileout, " *NODE_TM {\n" ); + fprintf ( fileout, " *NODE_NAME \"Object01\"\n" ); + fprintf ( fileout, " *INHERIT_POS 0 0 0\n" ); + fprintf ( fileout, " *INHERIT_ROT 0 0 0\n" ); + fprintf ( fileout, " *INHERIT_SCL 0 0 0\n" ); + fprintf ( fileout, " *TM_ROW0 1.0000 0.0000 0.0000\n" ); + fprintf ( fileout, " *TM_ROW1 0.0000 1.0000 0.0000\n" ); + fprintf ( fileout, " *TM_ROW2 0.0000 0.0000 1.0000\n" ); + fprintf ( fileout, " *TM_ROW3 0.0000 0.0000 0.0000\n" ); + fprintf ( fileout, " *TM_POS 0.0000 0.0000 0.0000\n" ); + fprintf ( fileout, " *TM_ROTAXIS 0.0000 0.0000 0.0000\n" ); + fprintf ( fileout, " *TM_ROTANGLE 0.0000\n" ); + fprintf ( fileout, " *TM_SCALE 1.0000 1.0000 1.0000\n" ); + fprintf ( fileout, " *TM_SCALEAXIS 0.0000 0.0000 0.0000\n" ); + fprintf ( fileout, " *TM_SCALEAXISANG 0.0000\n" ); + fprintf ( fileout, " }\n" ); + + text_num = text_num + 16; +/* + Sub block MESH: + Items +*/ + fprintf ( fileout, " *MESH {\n" ); + fprintf ( fileout, " *TIMEVALUE 0\n" ); + fprintf ( fileout, " *MESH_NUMVERTEX %d\n", cor3_num ); + fprintf ( fileout, " *MESH_NUMFACES %d\n", face_num ); + + text_num = text_num + 4; +/* + Sub sub block MESH_VERTEX_LIST +*/ + fprintf ( fileout, " *MESH_VERTEX_LIST {\n" ); + text_num = text_num + 1; + + for ( j = 0; j < cor3_num; j++ ) { + fprintf ( fileout, " *MESH_VERTEX %d %f %f %f\n", j, cor3[0][j], + cor3[1][j], cor3[2][j] ); + text_num = text_num + 1; + } + + fprintf ( fileout, " }\n" ); + text_num = text_num + 1; +/* + Sub sub block MESH_FACE_LIST + Items MESH_FACE +*/ + fprintf ( fileout, " *MESH_FACE_LIST {\n" ); + text_num = text_num + 1; + + for ( iface = 0; iface < face_num; iface++ ) { + + i1 = face[0][iface]; + i2 = face[1][iface]; + i3 = face[2][iface]; + + if ( face_order[iface] == 3 ) { + fprintf ( fileout, " *MESH_FACE %d: A: %d B: %d C: %d", iface, i1, i2, i3 ); + fprintf ( fileout, " AB: 1 BC: 1 CA: 1 *MESH_SMOOTHING *MESH_MTLID 1\n" ); + text_num = text_num + 1; + } + else if ( face_order[iface] == 4 ) { + i4 = face[3][iface]; + fprintf ( fileout, " *MESH_FACE %d: A: %d B: %d C: %d D: %d", iface, i1, i2, i3, i4 ); + fprintf ( fileout, " AB: 1 BC: 1 CD: 1 DA: 1 *MESH_SMOOTHING *MESH_MTLID 1\n" ); + text_num = text_num + 1; + } + } + + fprintf ( fileout, " }\n" ); + text_num = text_num + 1; +/* + Item MESH_NUMTVERTEX. +*/ + fprintf ( fileout, " *MESH_NUMTVERTEX 0\n" ); + text_num = text_num + 1; +/* + Item NUMCVERTEX. +*/ + fprintf ( fileout, " *MESH_NUMCVERTEX 0\n" ); + text_num = text_num + 1; +/* + Sub block MESH_NORMALS + Items MESH_FACENORMAL, MESH_VERTEXNORMAL (repeated) +*/ + fprintf ( fileout, " *MESH_NORMALS {\n" ); + text_num = text_num + 1; + + for ( iface = 0; iface < face_num; iface++ ) { + + fprintf ( fileout, " *MESH_FACENORMAL %d %f %f %f\n", + iface, face_normal[0][iface], face_normal[1][iface], face_normal[2][iface] ); + text_num = text_num + 1; + + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + fprintf ( fileout, " *MESH_VERTEXNORMAL %d %f %f %f\n", + face[ivert][iface], vertex_normal[0][ivert][iface], + vertex_normal[1][ivert][iface], vertex_normal[2][ivert][iface] ); + text_num = text_num + 1; + } + } + + fprintf ( fileout, " }\n" ); + text_num = text_num + 1; +/* + Close the MESH object. +*/ + fprintf ( fileout, " }\n" ); +/* + A few closing parameters. +*/ + fprintf ( fileout, " *PROP_MOTIONBLUR 0\n" ); + fprintf ( fileout, " *PROP_CASTSHADOW 1\n" ); + fprintf ( fileout, " *PROP_RECVSHADOW 1\n" ); +/* + Close the GEOM object. +*/ + fprintf ( fileout, "}\n" ); + + text_num = text_num + 5; +/* + Report. +*/ + printf ( "\n" ); + printf ( "ASE_WRITE - Wrote %d text lines;\n", text_num ); + + return SUCCESS; +} +/**********************************************************************/ + +int byu_read ( FILE *filein ) + +/**********************************************************************/ + +/* + Purpose: + + BYU_READ reads graphics data from a Movie.BYU surface geometry file. + + Discussion: + + A Movie.BYU surface geometry file contains 4 groups of data. + + The first group of data is a single line, containing 4 integers, + each one left justified in 8 columns. The integers are: + + PART_NUM, VERTEX_NUM, POLY_NUM, EDGE_NUM, + + that is, the number of parts or objects, the number of vertices or nodes, + the number of polygons or faces, and the number of edges. + + The second group of data is a single line, containing 2 integers, + each one left justified in 8 columnes. The integers are: + + POLY1, POLY2, + + the starting and ending polygon numbers. Presumably, this means + that the polygons are labeled POLY1, POLY1+1, ..., POLY2, comprising + a total of POLY_NUM polygons. + + The third group is the X, Y and Z coordinates of all the vertices. + These may be written using a FORTRAN format of 6E12.5, which + crams two sets of (X,Y,Z) data onto each line, with each real value + written in an exponential format with 5 places after the decimal. + However, it is generally possible to write the XYZ coordinate data + for each vertex on a separate line. + + The fourth group defines the polygons in terms of the vertex indices. + For each polygon, the vertices that make up the polygon are listed in + counterclockwise order. The last vertex listed is given with a negative + sign to indicate the end of the list. All the vertices for all the + polygons are listed one after the other, using a format that puts + up to 10 left-justified integers on a line, with each integer occupying + 8 spaces. + + This code will certainly read a BYU file created by BYU_WRITE, but + it will not handle more general files. In particular, an object + can have several parts, the coordinate data can be grouped so + that there are 2 sets of (x,y,z) data per line, and so on. + + Example: + + 1 8 6 24 + 1 6 + 0.00000E+00 0.00000E+00 0.00000E+00 + 1.00000E+00 0.00000E+00 0.00000E+00 + 1.00000E+00 2.00000E+00 0.00000E+00 + 0.00000E+00 2.00000E+00 0.00000E+00 + 0.00000E+00 0.00000E+00 1.00000E+00 + 1.00000E+00 0.00000E+00 1.00000E+00 + 1.00000E+00 2.00000E+00 1.00000E+00 + 0.00000E+00 2.00000E+00 1.00000E+00 + 4 3 2 -1 + 5 6 7 -8 + 1 5 8 -4 + 4 8 7 -3 + 3 7 6 -2 + 2 6 5 -1 + + Modified: + + 24 May 2001 + + Author: + + John Burkardt + +*/ +{ + int cor3_num_new; + int count; + int edge_num; + int face_num_new; + int iface; + int ival; + int ivert; + int j; + char *next; + int part_num; + int poly1; + int poly2; + int text_num; + int width; + float x; + float y; + float z; + + text_num = 0; + + if ( fgets ( input, LINE_MAX_LEN, filein ) == NULL ) { + return ERROR; + } + text_num = text_num + 1; + + sscanf ( input, "%d %d %d %d", &part_num, &cor3_num_new, &face_num_new, + &edge_num ); + + if ( fgets ( input, LINE_MAX_LEN, filein ) == NULL ) { + return ERROR; + } + text_num = text_num + 1; + + sscanf ( input, "%d %d", &poly1, &poly2 ); + + for ( j = cor3_num; j < cor3_num + cor3_num_new; j++ ) { + + if ( fgets ( input, LINE_MAX_LEN, filein ) == NULL ) { + return ERROR; + } + text_num = text_num + 1; + + sscanf ( input, "%f %f %f", &x, &y, &z ); + cor3[0][j] = x; + cor3[1][j] = y; + cor3[2][j] = z; + } + + for ( iface = face_num; iface < face_num + face_num_new; iface++ ) { + + if ( fgets ( input, LINE_MAX_LEN, filein ) == NULL ) { + return ERROR; + } + text_num = text_num + 1; + + next = input; + ivert = 0; + + for (;;) { + + count = sscanf ( next, "%d%n", &ival, &width ); + next = next + width; + + if ( count <= 0 ) { + return ERROR; + } + + if ( ival > 0 ) { + face[ivert][iface] = ival - 1 + cor3_num; + } + else { + face[ivert][iface] = - ival - 1 - cor3_num; + break; + } + + ivert = ivert + 1; + + } + face_order[iface] = ivert + 1; + } + + cor3_num = cor3_num + cor3_num_new; + face_num = face_num + face_num_new; +/* + Report. +*/ + printf ( "\n" ); + printf ( "BYU_READ - Read %d text lines.\n", text_num ); + + return SUCCESS; +} +/**********************************************************************/ + +int byu_write ( FILE *fileout ) + +/**********************************************************************/ + +/* + Purpose: + + BYU_WRITE writes out the graphics data as a Movie.BYU surface geometry file. + + Discussion: + + A Movie.BYU surface geometry file contains 4 groups of data. + + The first group of data is a single line, containing 4 integers, + each one left justified in 8 columns. The integers are: + + PART_NUM, VERTEX_NUM, POLY_NUM, EDGE_NUM, + + that is, the number of parts or objects, the number of vertices or nodes, + the number of polygons or faces, and the number of edges. + + The second group of data is a single line, containing 2 integers, + each one left justified in 8 columnes. The integers are: + + POLY1, POLY2, + + the starting and ending polygon numbers. Presumably, this means + that the polygons are labeled POLY1, POLY1+1, ..., POLY2, comprising + a total of POLY_NUM polygons. + + The third group is the X, Y and Z coordinates of all the vertices. + These may be written using a FORTRAN format of 6E12.5, which + crams two sets of (X,Y,Z) data onto each line, with each real value + written in an exponential format with 5 places after the decimal. + However, it is generally possible to write the XYZ coordinate data + for each vertex on a separate line. + + The fourth group defines the polygons in terms of the vertex indices. + For each polygon, the vertices that make up the polygon are listed in + counterclockwise order. The last vertex listed is given with a negative + sign to indicate the end of the list. All the vertices for all the + polygons are listed one after the other, using a format that puts + up to 10 left-justified integers on a line, with each integer occupying + 8 spaces. + + Example: + + 1 8 6 24 + 1 6 + 0.00000E+00 0.00000E+00 0.00000E+00 + 1.00000E+00 0.00000E+00 0.00000E+00 + 1.00000E+00 2.00000E+00 0.00000E+00 + 0.00000E+00 2.00000E+00 0.00000E+00 + 0.00000E+00 0.00000E+00 1.00000E+00 + 1.00000E+00 0.00000E+00 1.00000E+00 + 1.00000E+00 2.00000E+00 1.00000E+00 + 0.00000E+00 2.00000E+00 1.00000E+00 + 4 3 2 -1 + 5 6 7 -8 + 1 5 8 -4 + 4 8 7 -3 + 3 7 6 -2 + 2 6 5 -1 + + Modified: + + 24 May 2001 + + Author: + + John Burkardt +*/ +{ + int edge_num; + int iface; + int ivert; + int j; + int jp; + int part_num; + int text_num; + + text_num = 0; + + edge_num = 0; + for ( iface = 0; iface < face_num; iface++ ) { + edge_num = edge_num + face_order[iface]; + } + + part_num = 1; + + fprintf ( fileout, "%d %d %d %d\n", part_num, cor3_num, face_num, edge_num ); + text_num = text_num + 1; + + fprintf ( fileout, "1 %d\n", face_num ); + text_num = text_num + 1; + + for ( j = 0; j < cor3_num; j++ ) { + fprintf ( fileout, "%f %f %f\n", cor3[0][j], cor3[1][j], cor3[2][j] ); + text_num = text_num + 1; + } + + for ( iface = 0; iface < face_num; iface++ ) { + + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + + jp = face[ivert][iface] + 1; + if ( ivert == face_order[iface] - 1 ) { + jp = - jp; + } + fprintf ( fileout, "%d ", jp ); + } + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + } +/* + Report. +*/ + printf ( "\n" ); + printf ( "BYU_WRITE - Wrote %d text lines.\n", text_num ); + + return SUCCESS; +} +/******************************************************************************/ + +int char_index_last ( char* string, char c ) + +/******************************************************************************/ + +/* + Purpose: + + CHAR_INDEX_LAST reports the last occurrence of a character in a string. + + Author: + + John Burkardt +*/ +{ + int i; + int j; + int nchar; + + j = -1; + + nchar = strlen ( string ); + + for ( i = 0; i < nchar; i++ ) { + if ( string[i] == c ) { + j = i; + } + } + + return j; + +} +/******************************************************************************/ + +int char_pad ( int *char_index, int *null_index, char *string, + int STRING_MAX ) + +/******************************************************************************/ + +/* + Purpose: + + CHAR_PAD "pads" a character in a string with a blank on either side. + + Modified: + + 16 October 1998 + + Author: + + John Burkardt + + Parameters: + + Input/output, int *CHAR_INDEX, the position of the character to be padded. + On output, this is increased by 1. + + Input/output, int *NULL_INDEX, the position of the terminating NULL in + the string. On output, this is increased by 2. + + Input/output, char STRING[STRING_MAX], the string to be manipulated. + + Input, int STRING_MAX, the maximum number of characters that can be stored + in the string. + + Output, int CHAR_PAD, is SUCCESS if the operation worked, and ERROR otherwise. +*/ +{ + int i; + + if ( *char_index < 0 || + *char_index >= *null_index || + *char_index > STRING_MAX-1 ) { + return ERROR; + } + + if ( (*null_index) + 2 > STRING_MAX-1 ) { + return ERROR; + } + + for ( i = *null_index + 2; i > *char_index + 2; i-- ) { + string[i] = string[i-2]; + } + string[*char_index+2] = ' '; + string[*char_index+1] = string[*char_index]; + string[*char_index] = ' '; + + *char_index = *char_index + 1; + *null_index = *null_index + 2; + + return SUCCESS; +} +/******************************************************************************/ + +char char_read ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + CHAR_READ reads one character from a binary file. + + Modified: + + 24 May 1999 + + Author: + + John Burkardt +*/ +{ + char c; + + c = ( char ) fgetc ( filein ); + + return c; +} +/******************************************************************************/ + +int char_write ( FILE *fileout, char c ) + +/******************************************************************************/ + +/* + Purpose: + + CHAR_WRITE writes one character to a binary file. + + Modified: + + 24 May 1999 + + Author: + + John Burkardt +*/ +{ + fputc ( c, fileout ); + + return 1; +} +/******************************************************************************/ + +int command_line ( char **argv ) + +/******************************************************************************/ + +/* + + Purpose: + + COMMAND_LINE carries out a command-line session of file conversion. + + Discussion: + + This routine is invoked when the user command is something like + + ivcon filein_name fileout_name + + or + + ivcon -rn filein_name fileout_name + + where "-rn" signals the "reverse normals" option, or + + ivcon -rf filein_name fileout_name + + where "-rf" signals the "reverse faces" option. + + Modified: + + 28 June 1999 + + Author: + + John Burkardt +*/ +{ + int i; + int iarg; + int icor3; + int ierror; + int iface; + int ivert; + int reverse_faces; + int reverse_normals; +/* + Initialize local data. +*/ + iarg = 0; + ierror = 0; + reverse_faces = FALSE; + reverse_normals = FALSE; +/* + Initialize the graphics data. +*/ + data_init ( ); +/* + Get the -RN option, -RF option, and the input file name. +*/ + iarg = iarg + 1; + strcpy ( filein_name, argv[iarg] ); + + if ( leqi ( filein_name, "-RN" ) == TRUE ) { + reverse_normals = TRUE; + printf ( "\n" ); + printf ( "COMMAND_LINE: Reverse_Normals option requested.\n" ); + iarg = iarg + 1; + strcpy ( filein_name, argv[iarg] ); + } + + if ( leqi ( filein_name, "-RF" ) == TRUE ) { + reverse_faces = TRUE; + printf ( "\n" ); + printf ( "COMMAND_LINE: Reverse_Faces option requested.\n" ); + iarg = iarg + 1; + strcpy ( filein_name, argv[iarg] ); + } +/* + Read the input. +*/ + ierror = data_read ( ); + + if ( ierror == ERROR ) { + printf ( "\n" ); + printf ( "COMMAND_LINE - Fatal error!\n" ); + printf ( " Failure while reading input data.\n" ); + return ERROR; + } +/* + Reverse the normal vectors if requested. +*/ + if ( reverse_normals == TRUE ) { + + for ( icor3 = 0; icor3 < cor3_num; icor3++ ) { + for ( i = 0; i < 3; i++ ) { + cor3_normal[i][icor3] = - cor3_normal[i][icor3]; + } + } + + for ( iface = 0; iface < face_num; iface++ ) { + for ( i = 0; i < 3; i++ ) { + face_normal[i][iface] = - face_normal[i][iface]; + } + } + + for ( iface = 0; iface < face_num; iface++ ) { + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + for ( i = 0; i < 3; i++ ) { + vertex_normal[i][ivert][iface] = + - vertex_normal[i][ivert][iface]; + } + } + } + printf ( "\n" ); + printf ( "COMMAND_LINE - Note:\n" ); + printf ( " Reversed node, face, and vertex normals.\n" ); + } +/* + Reverse the faces if requested. +*/ + if ( reverse_faces == TRUE ) { + + face_reverse_order ( ); + + printf ( "\n" ); + printf ( "COMMAND_LINE - Note:\n" ); + printf ( " Reversed the face definitions.\n" ); + } +/* + Write the output file. +*/ + iarg = iarg + 1; + strcpy ( fileout_name, argv[iarg] ); + + ierror = data_write ( ); + + if ( ierror == ERROR ) { + printf ( "\n" ); + printf ( "COMMAND_LINE - Fatal error!\n" ); + printf ( " Failure while writing output data.\n" ); + return ERROR; + } + return SUCCESS; +} +/******************************************************************************/ + +void cor3_normal_set ( void ) + +/******************************************************************************/ + +/* + Purpose: + + COR3_NORMAL_SET computes node normal vectors. + + Modified: + + 18 November 1998 + + Author: + + John Burkardt +*/ +{ + int icor3; + int iface; + int ivert; + int j; + float norm; + float temp; + + for ( icor3 = 0; icor3 < cor3_num; icor3++ ) { + for ( j = 0; j < 3; j++ ) { + cor3_normal[j][icor3] = 0.0; + } + } +/* + Add up the normals at all the faces to which the node belongs. +*/ + for ( iface = 0; iface < face_num; iface++ ) { + + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + + icor3 = face[ivert][iface]; + + for ( j = 0; j < 3; j++ ) { + cor3_normal[j][icor3] = cor3_normal[j][icor3] + + vertex_normal[j][ivert][iface]; + } + } + } +/* + Renormalize. +*/ + for ( icor3 = 0; icor3 < cor3_num; icor3++ ) { + + norm = 0.0; + for ( j = 0; j < 3; j++ ) { + temp = cor3_normal[j][icor3]; + norm = norm + temp * temp; + } + + if ( norm == 0.0 ) { + norm = 3.0; + for ( j = 0; j < 3; j++ ) { + cor3_normal[j][icor3] = 1.0; + } + } + + norm = ( float ) sqrt ( norm ); + + for ( j = 0; j < 3; j++ ) { + cor3_normal[j][icor3] = cor3_normal[j][icor3] / norm; + } + } + + return; +} +/******************************************************************************/ + +void cor3_range ( void ) + +/******************************************************************************/ + +/* + Purpose: + + COR3_RANGE computes the coordinate minima and maxima. + + Modified: + + 31 August 1998 + + Author: + + John Burkardt +*/ +{ + int i; + float xave; + float xmax; + float xmin; + float yave; + float ymax; + float ymin; + float zave; + float zmax; + float zmin; + + xave = cor3[0][0]; + xmax = cor3[0][0]; + xmin = cor3[0][0]; + + yave = cor3[1][0]; + ymax = cor3[1][0]; + ymin = cor3[1][0]; + + zave = cor3[2][0]; + zmax = cor3[2][0]; + zmin = cor3[2][0]; + + for ( i = 1; i < cor3_num; i++ ) { + + xave = xave + cor3[0][i]; + if ( cor3[0][i] < xmin ) { + xmin = cor3[0][i]; + } + if ( cor3[0][i] > xmax ) { + xmax = cor3[0][i]; + } + + yave = yave + cor3[1][i]; + if ( cor3[1][i] < ymin ) { + ymin = cor3[1][i]; + } + if ( cor3[1][i] > ymax ) { + ymax = cor3[1][i]; + } + + zave = zave + cor3[2][i]; + if ( cor3[2][i] < zmin ) { + zmin = cor3[2][i]; + } + if ( cor3[2][i] > zmax ) { + zmax = cor3[2][i]; + } + } + + xave = xave / cor3_num; + yave = yave / cor3_num; + zave = zave / cor3_num; + + printf ( "\n" ); + printf ( "COR3_RANGE - Data range:\n" ); + printf ( "\n" ); + printf ( " Minimum Average Maximum Range\n" ); + printf ( "\n" ); + printf ( "X %f %f %f %f\n", xmin, xave, xmax, xmax-xmin ); + printf ( "Y %f %f %f %f\n", ymin, yave, ymax, ymax-ymin ); + printf ( "Z %f %f %f %f\n", zmin, zave, zmax, zmax-zmin ); + +} +/******************************************************************************/ + +void data_check ( void ) + +/******************************************************************************/ + +/* + Purpose: + + DATA_CHECK checks the input data. + + Modified: + + 18 May 1999 + + Author: + + John Burkardt +*/ +{ + int iface; + int nfix; + + if ( color_num > COLOR_MAX ) { + printf ( "\n" ); + printf ( "DATA_CHECK - Warning!\n" ); + printf ( " The input data requires %d colors.\n", color_num ); + printf ( " There was only room for %d\n", COLOR_MAX ); + color_num = COLOR_MAX; + } + + if ( cor3_num > COR3_MAX ) { + printf ( "\n" ); + printf ( "DATA_CHECK - Warning!\n" ); + printf ( " The input data requires %d points.\n", cor3_num ); + printf ( " There was only room for %d\n", COR3_MAX ); + cor3_num = COR3_MAX; + } + + if ( face_num > FACE_MAX ) { + printf ( "\n" ); + printf ( "DATA_CHECK - Warning!\n" ); + printf ( " The input data requires %d faces.\n", face_num ); + printf ( " There was only room for %d\n", FACE_MAX ); + face_num = FACE_MAX; + } + + if ( line_num > LINES_MAX ) { + printf ( "\n" ); + printf ( "DATA_CHECK - Warning!\n" ); + printf ( " The input data requires %d line items.\n", line_num ); + printf ( " There was only room for %d.\n", LINES_MAX ); + line_num = LINES_MAX; + } + + nfix = 0; + + for ( iface = 0; iface < face_num; iface++ ) { + + if ( face_order[iface] > ORDER_MAX ) { + face_order[iface] = ORDER_MAX; + nfix = nfix + 1; + } + + } + + if ( nfix > 0 ) { + printf ( "\n" ); + printf ( "DATA_CHECK - Warning!\n" ); + printf ( " Corrected %d faces using more than %d vertices per face.\n", + nfix, ORDER_MAX ); + } + + for ( i = 0; i < material_num; i++ ) { + if ( strcmp ( material_name[i], "" ) == 0 ) { + strcpy ( material_name[i], "Material_0000" ); + } + } + + for ( i = 0; i < texture_num; i++ ) { + if ( strcmp ( texture_name[i], "" ) == 0 ) { + strcpy ( texture_name[i], "Texture_0000" ); + } + } + + printf ( "\n" ); + printf ( "DATA_CHECK - Data checked.\n" ); + + return; +} +/******************************************************************************/ + +void data_init ( void ) + +/******************************************************************************/ + +/* + Purpose: + + DATA_INIT initializes the internal graphics data. + + Modified: + + 04 July 2000 + + Author: + + John Burkardt +*/ +{ + int i; + int iface; + int ivert; + int j; + int k; + + strcpy( anim_name, "" ); + + for ( i = 0; i < 3; i++ ) { + background_rgb[i] = 0.0; + } + + for ( i = 0; i < 3; i++ ) { + for ( j = 0; j < COR3_MAX; j++ ) { + cor3[i][j] = 0.0; + } + } + + for ( i = 0; i < COR3_MAX; i++ ) { + cor3_material[i] = 0; + } + + for ( i = 0; i < 3; i++ ) { + for ( j = 0; j < COR3_MAX; j++ ) { + cor3_normal[i][j] = 0.0; + } + } + + for ( j = 0; j < COR3_MAX; j++ ) { + cor3_tex_uv[0][j] = 0.0; + cor3_tex_uv[1][j] = 0.0; + } + + for ( iface = 0; iface < FACE_MAX; iface++ ) { + for ( ivert = 0; ivert < ORDER_MAX; ivert++ ) { + face[ivert][iface] = 0; + } + } + + for ( iface = 0; iface < FACE_MAX; iface++ ) { + face_flags[iface] = 6; + } + + for ( iface = 0; iface < FACE_MAX; iface++ ) { + face_material[iface] = 0; + } + + for ( iface = 0; iface < FACE_MAX; iface++ ) { + for ( i = 0; i < 3; i++ ) { + face_normal[i][iface] = 0; + } + } + + for ( iface = 0; iface < FACE_MAX; iface++ ) { + face_object[iface] = -1; + } + + for ( iface = 0; iface < FACE_MAX; iface++ ) { + face_order[iface] = 0; + } + + for ( iface = 0; iface < FACE_MAX; iface++ ) { + face_smooth[iface] = 1; + } + + for ( i = 0; i < LINES_MAX; i++ ) { + line_dex[i] = -1; + } + + for ( i = 0; i < LINES_MAX; i++ ) { + line_material[i] = 0; + } + + strcpy ( material_binding, "DEFAULT" ); + + for ( j = 0; j < MATERIAL_MAX; j++ ) { + strcpy ( material_name[j], "Material_0000" ); + } + + for ( i = 0; i < 4; i++ ) { + for ( j = 0; j < MATERIAL_MAX; j++ ) { + material_rgba[i][j] = 0.0; + } + } + + strcpy ( normal_binding, "DEFAULT" ); + + for ( j = 0; j < ORDER_MAX*FACE_MAX; j++ ) { + for ( i = 0; i < 3; i++ ) { + normal_temp[i][j] = 0; + } + } + + color_num = 0; + cor3_num = 0; + face_num = 0; + group_num = 0; + line_num = 0; + material_num = 0; + object_num = 0; + texture_num = 0; + + strcpy ( object_name, "IVCON" ); + + for ( i = 0; i < 3; i++ ) { + origin[i] = 0.0; + } + + for ( i = 0; i < 3; i++ ) { + pivot[i] = 0.0; + } + + for ( j = 0; j < COLOR_MAX; j++ ) { + rgbcolor[0][j] = 0.299; + rgbcolor[1][j] = 0.587; + rgbcolor[2][j] = 0.114; + } + + strcpy ( texture_binding, "DEFAULT" ); + + for ( j = 0; j < TEXTURE_MAX; j++ ) { + strcpy ( texture_name[j], "Texture_0000" ); + } + + tmat_init ( transform_matrix ); + + for ( iface = 0; iface < FACE_MAX; iface++ ) { + for ( ivert = 0; ivert < ORDER_MAX; ivert++ ) { + vertex_material[ivert][iface] = 0; + } + } + + for ( iface = 0; iface < FACE_MAX; iface++ ) { + for ( ivert = 0; ivert < ORDER_MAX; ivert++ ) { + for ( i = 0; i < 3; i++ ) { + vertex_normal[i][ivert][iface] = 0.0; + } + } + } + + for ( j = 0; j < 3; j++ ) { + for ( k = 0; k < FACE_MAX; k++ ) { + vertex_rgb[0][j][k] = 0.299; + vertex_rgb[1][j][k] = 0.587; + vertex_rgb[2][j][k] = 0.114; + } + } + + for ( iface = 0; iface < FACE_MAX; iface++ ) { + for ( ivert = 0; ivert < ORDER_MAX; ivert++ ) { + for ( i = 0; i < 2; i++ ) { + vertex_tex_uv[i][ivert][iface] = 0.0; + } + } + } + + if ( debug ) { + printf ( "\n" ); + printf ( "DATA_INIT: Graphics data initialized.\n" ); + } + + return; +} +/******************************************************************************/ + +int data_read ( void ) + +/******************************************************************************/ + +/* + Purpose: + + DATA_READ reads a file into internal graphics data. + + Modified: + + 26 September 1999 + + Author: + + John Burkardt +*/ +{ + FILE *filein; + char *filein_type; + int icor3; + int ierror; + int iface; + int iline; + int ivert; + int ntemp; +/* + Retrieve the input file type. +*/ + filein_type = file_ext ( filein_name ); + + if ( filein_type == NULL ) { + printf ( "\n" ); + printf ( "DATA_READ - Fatal error!\n" ); + printf ( " Could not determine the type of '%s'.\n", filein_name ); + return ERROR; + } + else if ( debug ) { + printf ( "\n" ); + printf ( "DATA_READ: Input file has type %s.\n", filein_type ); + } +/* + Initialize some data. +*/ + max_order2 = 0; + bad_num = 0; + bytes_num = 0; + comment_num = 0; + dup_num = 0; + text_num = 0; +/* + Open the file. +*/ + if ( leqi ( filein_type, "3DS" ) == TRUE || + leqi ( filein_type, "STLB" ) == TRUE || + leqi ( filein_type, "TRIB" ) == TRUE ) { + filein = fopen ( filein_name, "rb" ); + } + else { + filein = fopen ( filein_name, "r" ); + } + + if ( filein == NULL ) { + printf ( "\n" ); + printf ( "DATA_READ - Fatal error!\n" ); + printf ( " Could not open the input file '%s'!\n", filein_name ); + return ERROR; + } +/* + Read the information in the file. +*/ + if ( leqi ( filein_type, "3DS" ) == TRUE ) { + + ierror = tds_read ( filein ); +/* + Cleanup: distribute the node textures to the vertices. +*/ + if ( ierror == SUCCESS ) { + + for ( iface = 0; iface < face_num; iface++ ) { + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + icor3 = face[ivert][iface]; + vertex_tex_uv[0][ivert][iface] = cor3_tex_uv[0][icor3]; + vertex_tex_uv[1][ivert][iface] = cor3_tex_uv[1][icor3]; + } + } + + } + + } + else if ( leqi ( filein_type, "ASE" ) == TRUE ) { + + ierror = ase_read ( filein ); + + if ( ierror == SUCCESS ) { + + node_to_vertex_material ( ); + + vertex_to_face_material ( ); + + } + + } + else if ( leqi ( filein_type, "BYU" ) == TRUE ) { + + ierror = byu_read ( filein ); + + } + else if ( leqi ( filein_type, "DXF" ) == TRUE ) { + + ierror = dxf_read ( filein ); + + } + else if ( leqi ( filein_type, "GMOD" ) == TRUE ) { + + ierror = gmod_read ( filein ); + + } + else if ( leqi ( filein_type, "HRC" ) == TRUE ) { + + ierror = hrc_read ( filein ); + + } + else if ( leqi ( filein_type, "IV" ) == TRUE ) { + + ierror = iv_read ( filein ); + + } + else if ( leqi ( filein_type, "OBJ" ) == TRUE ) { + + ierror = obj_read ( filein ); + + } + else if ( leqi ( filein_type, "SMF" ) == TRUE ) { + + ierror = smf_read ( filein ); + + } + else if ( + leqi ( filein_type, "STL" ) == TRUE || + leqi ( filein_type, "STLA") == TRUE ) { + + ierror = stla_read ( filein ); + + if( ierror ) { + // might be binary + fclose(filein); + filein = fopen ( filein_name, "rb" ); + ierror = stlb_read ( filein ); + } + } + else if ( leqi ( filein_type, "STLB") == TRUE ) { + + ierror = stlb_read ( filein ); + + } + else if ( + leqi ( filein_type, "TRI" ) == TRUE || + leqi ( filein_type, "TRIA") == TRUE ) { + + ierror = tria_read ( filein ); + + } + else if ( leqi ( filein_type, "TRIB") == TRUE ) { + + ierror = trib_read ( filein ); + + } + else if ( leqi ( filein_type, "VLA" ) == TRUE ) { + + ierror = vla_read ( filein ); + + } + else { + printf ( "\n" ); + printf ( "DATA_READ - Fatal error!\n" ); + printf ( " Unacceptable input file type.\n" ); + return ERROR; + } + + fclose ( filein ); + + if ( debug ) { + printf ( "DATA_READ: Finished reading the data file.\n" ); + } +/* + Catch errors reported by the various reading routines. +*/ + if ( ierror == ERROR ) { + return ierror; + } +/* + Restore the transformation matrix. +*/ + tmat_init ( transform_matrix ); +/* + Report on what we read. +*/ + if ( face_num < FACE_MAX ) { + ntemp = face_num; + } + else { + ntemp = FACE_MAX; + } + + max_order2 = ivec_max ( ntemp, face_order ); + + data_report ( ); +/* + Warn about any errors that occurred during reading. +*/ + if ( ierror == ERROR ) { + printf ( "\n" ); + printf ( "DATA_READ - Fatal error!\n" ); + printf ( " An error occurred while reading the input file.\n" ); + return ERROR; + } +/* + Check the data. + You MUST wait until after this check before doing other computations, + since COR3_NUM and other variables could be much larger than the legal + maximums, until corrected by DATA_CHECK. +*/ + data_check ( ); +/* + MATERIALS FIXUPS: + + If there are no materials at all, define one. +*/ + if ( material_num < 1 ) { + material_num = 1; + strcpy ( material_name[0], "Material_0000" ); + material_rgba[0][0] = 0.7; + material_rgba[1][0] = 0.7; + material_rgba[2][0] = 0.7; + material_rgba[3][0] = 1.0; + } +/* + If a node has not been assigned a material, set it to material 0. +*/ + for ( icor3 = 0; icor3 < cor3_num; icor3++ ) { + if ( cor3_material[icor3] < 0 || cor3_material[icor3] > material_num - 1 ) { + cor3_material[icor3] = 0; + } + } +/* + If a vertex has not been assigned a material, set it to material 0. +*/ + for ( iface = 0; iface < face_num; iface++ ) { + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + if ( vertex_material[ivert][iface] < 0 || vertex_material[ivert][iface] > material_num - 1 ) { + vertex_material[ivert][iface] = 0; + } + } + } +/* + If a face has not been assigned a material, set it to material 0. +*/ + for ( iface = 0; iface < face_num; iface++ ) { + if ( face_material[iface] < 0 || face_material[iface] > material_num - 1 ) { + face_material[iface] = 0; + } + } +/* + If a line item has not been assigned a material, set it to material 0. +*/ + for ( iline = 0; iline < line_num; iline++ ) { + if ( line_dex[iline] == -1 ) { + line_material[iline] = -1; + } + else if ( line_material[iline] < 0 || line_material[iline] > material_num - 1 ) { + line_material[iline] = 0; + } + } +/* + Delete edges of zero length. +*/ + edge_null_delete ( ); +/* + Compute the area of each face. +*/ + face_area_set ( ); +/* + Delete faces with zero area. +*/ + face_null_delete ( ); +/* + Recompute zero face-vertex normals from vertex positions. +*/ + vertex_normal_set ( ); +/* + Compute the node normals from the vertex normals. +*/ + cor3_normal_set ( ); +/* + Recompute zero face normals by averaging face-vertex normals. +*/ + face_normal_ave ( ); +/* + Report on the nodal coordinate range. +*/ + cor3_range ( ); + + return SUCCESS; +} +/**********************************************************************/ + +void data_report ( void ) + +/**********************************************************************/ + +/* + Purpose: + + DATA_REPORT gives a summary of the contents of the data file. + + Modified: + + 24 May 1999 + + Author: + + John Burkardt +*/ +{ + printf ( "\n" ); + printf ( "DATA_REPORT - The input file contains:\n" ); + printf ( "\n" ); + printf ( " Bad data items %d\n", bad_num ); + printf ( " Text lines %d\n", text_num ); + printf ( " Text bytes (binary data) %d\n", bytes_num ); + printf ( " Colors %d\n", color_num ); + printf ( " Comments %d\n", comment_num ); + printf ( " Duplicate points %d\n", dup_num ); + printf ( " Faces %d\n", face_num ); + printf ( " Groups %d\n", group_num ); + printf ( " Vertices per face, maximum %d\n", max_order2 ); + printf ( " Line items %d\n", line_num ); + printf ( " Points %d\n", cor3_num ); + printf ( " Objects %d\n", object_num ); + + return; +} +/******************************************************************************/ + +int data_write ( void ) + +/******************************************************************************/ + +/* + Purpose: + + DATA_WRITE writes the internal graphics data to a file. + + Modified: + + 22 May 1999 + + Author: + + John Burkardt +*/ +{ + FILE *fileout; + char *fileout_type; + int line_num_save; + int result; + + result = SUCCESS; +/* + Retrieve the output file type. +*/ + fileout_type = file_ext ( fileout_name ); + + if ( fileout_type == NULL ) { + printf ( "\n" ); + printf ( "DATA_WRITE - Fatal error!\n" ); + printf ( " Could not determine the output file type.\n" ); + return ERROR; + } +/* + Open the output file. +*/ + if ( leqi ( fileout_type, "3DS" ) == TRUE || + leqi ( fileout_type, "STLB" ) == TRUE || + leqi ( fileout_type, "TRIB" ) ) { + fileout = fopen ( fileout_name, "wb" ); + } + else { + fileout = fopen ( fileout_name, "w" ); + } + + if ( fileout == NULL ) { + printf ( "\n" ); + printf ( "DATA_WRITE - Fatal error!\n" ); + printf ( " Could not open the output file!\n" ); + return ERROR; + } +/* + Write the output file. +*/ + if ( leqi ( fileout_type, "3DS" ) == TRUE ) { + + tds_pre_process(); + result = tds_write ( fileout ); + + } + else if ( leqi ( fileout_type, "ASE" ) == TRUE ) { + + result = ase_write ( fileout ); + + } + else if ( leqi ( fileout_type, "BYU" ) == TRUE ) { + + result = byu_write ( fileout ); + + } + else if ( leqi ( fileout_type, "DXF" ) == TRUE ) { + + result = dxf_write ( fileout ); + + } + else if ( leqi ( fileout_type, "GMOD" ) == TRUE ) { + + result = gmod_write ( fileout ); + + } + else if ( leqi ( fileout_type, "HRC" ) == TRUE ) { + + result = hrc_write ( fileout ); + + } + else if ( leqi ( fileout_type, "IV" ) == TRUE ) { + + result = iv_write ( fileout ); + + } + else if ( leqi ( fileout_type, "OBJ" ) == TRUE ) { + + result = obj_write ( fileout ); + + } + else if ( leqi ( fileout_type, "POV" ) == TRUE ) { + + result = pov_write ( fileout ); + + } + else if ( leqi ( fileout_type, "SMF" ) == TRUE ) { + + result = smf_write ( fileout ); + + } + else if ( + leqi ( fileout_type, "STL" ) == TRUE || + leqi ( fileout_type, "STLA" ) == TRUE ) { + + result = stla_write ( fileout ); + + } + else if ( leqi ( fileout_type, "STLB" ) == TRUE ) { + + result = stlb_write ( fileout ); + + } + else if ( leqi ( fileout_type, "TEC" ) == TRUE ) { + + result = tec_write ( fileout ); + + } + else if ( + leqi ( fileout_type, "TRI" ) == TRUE || + leqi ( fileout_type, "TRIA" ) == TRUE ) { + + result = tria_write ( fileout ); + + } + else if ( leqi ( fileout_type, "TRIB" ) == TRUE ) { + + result = trib_write ( fileout ); + + } + else if ( leqi ( fileout_type, "TXT" ) == TRUE ) { + + result = txt_write ( fileout ); + + } + else if ( leqi ( fileout_type, "UCD" ) == TRUE ) { + + result = ucd_write ( fileout ); + + } + else if ( leqi ( fileout_type, "VLA" ) == TRUE ) { + + line_num_save = line_num; + + if ( face_num > 0 ) { + + printf ( "\n" ); + printf ( "DATA_WRITE - Note:\n" ); + printf ( " Face information will temporarily be converted to\n" ); + printf ( " line information for output to a VLA file.\n" ); + + face_to_line ( ); + + if ( line_num > LINES_MAX ) { + printf ( "\n" ); + printf ( "DATA_WRITE - Warning:\n" ); + printf ( " Some face information was lost.\n" ); + printf ( " The maximum number of lines is %d.\n", LINES_MAX ); + printf ( " The number of lines needed is %d.\n", line_num ); + line_num = LINES_MAX; + } + + } + + result = vla_write ( fileout ); + + line_num = line_num_save; + + } + else if ( leqi ( fileout_type, "WRL" ) == TRUE ) { + + result = wrl_write ( fileout ); + + } + else if ( leqi ( fileout_type, "XGL" ) == TRUE ) { + + result = xgl_write ( fileout ); + + } + else { + + result = ERROR; + printf ( "\n" ); + printf ( "DATA_WRITE - Fatal error!\n" ); + printf ( " Unacceptable output file type \"%s\".\n", fileout_type ); + + } +/* + Close the output file. +*/ + fclose ( fileout ); + + if ( result == ERROR ) { + return ERROR; + } + else { + return SUCCESS; + } +} +/******************************************************************************/ + +int dxf_read ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + DXF_READ reads an AutoCAD DXF file. + + Examples: + + 0 + SECTION + 2 + HEADER + 999 + diamond.dxf created by IVREAD. + 999 + Original data in diamond.obj. + 0 + ENDSEC + 0 + SECTION + 2 + TABLES + 0 + ENDSEC + 0 + SECTION + 2 + BLOCKS + 0 + ENDSEC + 0 + SECTION + 2 + ENTITIES + 0 + LINE + 8 + 0 + 10 + 0.00 (X coordinate of beginning of line.) + 20 + 0.00 (Y coordinate of beginning of line.) + 30 + 0.00 (Z coordinate of beginning of line.) + 11 + 1.32 (X coordinate of end of line.) + 21 + 1.73 (Y coordinate of end of line.) + 31 + 2.25 (Z coordinate of end of line.) + 0 + 3DFACE + 8 + Cube + 10 + -0.50 (X coordinate of vertex 1) + 20 + 0.50 (Y coordinate of vertex 1) + 30 + 1.0 (Z coordinate of vertex 1) + 11 + 0.50 (X coordinate of vertex 2) + 21 + 0.50 (Y coordinate of vertex 2) + 31 + 1.0 (Z coordinate of vertex 2) + 12 + 0.50 (X coordinate of vertex 3) + 22 + 0.50 (Y coordinate of vertex 3) + 32 + 0.00 (Z coordinate of vertex 3) + 0 + ENDSEC + 0 + EOF + + Modified: + + 23 May 1999 + + Author: + + John Burkardt +*/ +{ + int code; + int count; + float cvec[3]; + int icor3; + char input1[LINE_MAX_LEN]; + char input2[LINE_MAX_LEN]; + int ivert; + float rval; + int width; + int linemode; + int cpos; + + linemode = 0; + ivert = 0; +/* + Read the next two lines of the file into INPUT1 and INPUT2. +*/ + + for ( ;; ) { + +/* + INPUT1 should contain a single integer, which tells what INPUT2 + will contain. +*/ + if ( fgets ( input1, LINE_MAX_LEN, filein ) == NULL ) { + break; + } + + text_num = text_num + 1; + + count = sscanf ( input1, "%d%n", &code, &width ); + if ( count <= 0 ) { + break; + } +/* + Read the second line, and interpret it according to the code. +*/ + if ( fgets ( input2, LINE_MAX_LEN, filein ) == NULL ) { + break; + } + + text_num = text_num + 1; + + if ( code == 0 ) { + + if ( ivert > 0 ) { + /* finish off the face */ + face_order[face_num] = ivert; + face_num = face_num + 1; + ivert = 0; + } + + if ( strncmp( input2, "LINE", 4 ) == 0 ) { + linemode = 1; + } + else if ( strncmp( input2, "3DFACE", 6 ) == 0 ) { + linemode = 0; + ivert = 0; + } + } + else { + + for (cpos = 0; input1[cpos] == ' '; cpos++) + {}; + + if ( input1[cpos] == '1' || input1[cpos] == '2' || input1[cpos] == '3' ) { + + count = sscanf ( input2, "%e%n", &rval, &width ); + + switch ( input1[cpos] ) + { + case '1': + if ( line_num > 0 ) { + if ( linemode ) { + line_dex[line_num] = - 1; + line_material[line_num] = - 1; + line_num = line_num + 1; + } + } + cvec[0] = rval; + break; + + case '2': + cvec[1] = rval; + break; + + case '3': + cvec[2] = rval; + + if ( cor3_num < 1000 ) { + icor3 = rcol_find ( cor3, 3, cor3_num, cvec ); + } + else { + icor3 = -1; + } + + if ( icor3 == -1 ) { + icor3 = cor3_num; + if ( cor3_num < COR3_MAX ) { + cor3[0][cor3_num] = cvec[0]; + cor3[1][cor3_num] = cvec[1]; + cor3[2][cor3_num] = cvec[2]; + } + cor3_num = cor3_num + 1; + } + else { + dup_num = dup_num + 1; + } + + if ( linemode ) { + line_dex[line_num] = icor3; + line_material[line_num] = 0; + line_num = line_num + 1; + } + else { + face[ivert][face_num] = icor3; + ivert = ivert + 1; + } + break; + + default: + break; + } + } + } + } + + if ( line_num > 0 ) { + if ( linemode ) { + line_dex[line_num] = - 1; + line_material[line_num] = - 1; + line_num = line_num + 1; + } + } + return SUCCESS; +} +/******************************************************************************/ + +int dxf_write ( FILE *fileout ) + +/******************************************************************************/ + +/* + Purpose: + + DXF_WRITE writes graphics information to an AutoCAD DXF file. + + Examples: + + 0 + SECTION + 2 + HEADER + 999 + diamond.dxf created by IVREAD. + 999 + Original data in diamond.obj. + 0 + ENDSEC + 0 + SECTION + 2 + TABLES + 0 + ENDSEC + 0 + SECTION + 2 + BLOCKS + 0 + ENDSEC + 0 + SECTION + 2 + ENTITIES + 0 + LINE + 8 + 0 + 10 + 0.00 (X coordinate of beginning of line.) + 20 + 0.00 (Y coordinate of beginning of line.) + 30 + 0.00 (Z coordinate of beginning of line.) + 11 + 1.32 (X coordinate of end of line.) + 21 + 1.73 (Y coordinate of end of line.) + 31 + 2.25 (Z coordinate of end of line.) + 0 + 3DFACE + 8 + Cube + 10 + -0.50 (X coordinate of vertex 1) + 20 + 0.50 (Y coordinate of vertex 1) + 30 + 1.0 (Z coordinate of vertex 1) + 11 + 0.50 (X coordinate of vertex 2) + 21 + 0.50 (Y coordinate of vertex 2) + 31 + 1.0 (Z coordinate of vertex 2) + 12 + 0.50 (X coordinate of vertex 3) + 22 + 0.50 (Y coordinate of vertex 3) + 32 + 0.00 (Z coordinate of vertex 3) + 0 + ENDSEC + 0 + EOF + + Modified: + + 16 May 1999 + + Author: + + John Burkardt +*/ +{ + int icor3; + int iline; + int iface; + int ivert; + int jcor3; + int newline; + int text_num; + +/* + Initialize. +*/ + text_num = 0; + + fprintf ( fileout, " 0\n" ); + fprintf ( fileout, "SECTION\n" ); + fprintf ( fileout, " 2\n" ); + fprintf ( fileout, "HEADER\n" ); + fprintf ( fileout, "999\n" ); + fprintf ( fileout, "%s created by IVCON.\n", fileout_name ); + fprintf ( fileout, "999\n" ); + fprintf ( fileout, "Original data in %s.\n", filein_name ); + fprintf ( fileout, " 0\n" ); + fprintf ( fileout, "ENDSEC\n" ); + text_num = text_num + 10; + + fprintf ( fileout, " 0\n" ); + fprintf ( fileout, "SECTION\n" ); + fprintf ( fileout, " 2\n" ); + fprintf ( fileout, "TABLES\n" ); + fprintf ( fileout, " 0\n" ); + fprintf ( fileout, "ENDSEC\n" ); + text_num = text_num + 6; + + fprintf ( fileout, " 0\n" ); + fprintf ( fileout, "SECTION\n" ); + fprintf ( fileout, " 2\n" ); + fprintf ( fileout, "BLOCKS\n" ); + fprintf ( fileout, " 0\n" ); + fprintf ( fileout, "ENDSEC\n" ); + text_num = text_num + 6; + + fprintf ( fileout, " 0\n" ); + fprintf ( fileout, "SECTION\n" ); + fprintf ( fileout, " 2\n" ); + fprintf ( fileout, "ENTITIES\n" ); + text_num = text_num + 4; +/* + Handle lines. +*/ + jcor3 = 0; + newline = TRUE; + + for ( iline = 0; iline < line_num; iline++ ) { + + icor3 = line_dex[iline]; + + if ( icor3 == -1 ) { + + newline = TRUE; + } + else { + + if ( newline == FALSE ) { + + fprintf ( fileout, " 0\n" ); + fprintf ( fileout, "LINE\n" ); + fprintf ( fileout, " 8\n" ); + fprintf ( fileout, " 0\n" ); + fprintf ( fileout, " 10\n" ); + fprintf ( fileout, "%f\n", cor3[0][jcor3] ); + fprintf ( fileout, " 20\n" ); + fprintf ( fileout, "%f\n", cor3[1][jcor3] ); + fprintf ( fileout, " 30\n" ); + fprintf ( fileout, "%f\n", cor3[2][jcor3] ); + fprintf ( fileout, " 11\n" ); + fprintf ( fileout, "%f\n", cor3[0][icor3] ); + fprintf ( fileout, " 21\n" ); + fprintf ( fileout, "%f\n", cor3[1][icor3] ); + fprintf ( fileout, " 31\n" ); + fprintf ( fileout, "%f\n", cor3[2][icor3] ); + + text_num = text_num + 16; + + } + + jcor3 = icor3; + newline = FALSE; + + } + } +/* + Handle faces. + (If FACE_ORDER is greater than 10, you're sure to have problems here) +*/ + for ( iface = 0; iface < face_num; iface++ ) { + + fprintf ( fileout, " 0\n" ); + fprintf ( fileout, "3DFACE\n" ); + fprintf ( fileout, " 8\n" ); + fprintf ( fileout, " Cube\n" ); + text_num = text_num + 4; + + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + + icor3 = face[ivert][iface]; + + fprintf ( fileout, "1%d\n", ivert ); + fprintf ( fileout, "%f\n", cor3[0][icor3] ); + fprintf ( fileout, "2%d\n", ivert ); + fprintf ( fileout, "%f\n", cor3[1][icor3] ); + fprintf ( fileout, "3%d\n", ivert ); + fprintf ( fileout, "%f\n", cor3[2][icor3] ); + + text_num = text_num + 6; + } + } + + fprintf ( fileout, " 0\n" ); + fprintf ( fileout, "ENDSEC\n" ); + fprintf ( fileout, " 0\n" ); + fprintf ( fileout, "EOF\n" ); + text_num = text_num + 4; +/* + Report. +*/ + printf ( "\n" ); + printf ( "DXF_WRITE - Wrote %d text lines.\n", text_num ); + + return SUCCESS; +} +/**********************************************************************/ + +void edge_null_delete ( void ) + +/**********************************************************************/ + +/* + Purpose: + + EDGE_NULL_DELETE deletes face edges with zero length. + + Modified: + + 16 July 1999 + + Author: + + John Burkardt +*/ +{ + float distsq; + int face2[ORDER_MAX]; + int face_order2; + int iface; + int inode; + int ivert; + int j; + int jnode; + int jvert; + int edge_num; + int edge_num_del; + float vertex_normal2[3][ORDER_MAX]; + float x; + float y; + float z; + + edge_num = 0; + edge_num_del = 0; +/* + Consider each face. +*/ + for ( iface = 0; iface < face_num; iface++ ) { +/* + Consider each pair of consecutive vertices. +*/ + face_order2 = 0; + + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + + edge_num = edge_num + 1; + + jvert = ivert + 1; + if ( jvert >= face_order[iface] ) { + jvert = 0; + } + + inode = face[ivert][iface]; + jnode = face[jvert][iface]; + + + x = cor3[0][inode] - cor3[0][jnode]; + y = cor3[1][inode] - cor3[1][jnode]; + z = cor3[2][inode] - cor3[2][jnode]; + + distsq = x * x + y * y + z * z; + + if ( distsq != 0.0 ) { + face2[face_order2] = face[ivert][iface]; + vertex_normal2[0][face_order2] = vertex_normal[0][ivert][iface]; + vertex_normal2[1][face_order2] = vertex_normal[1][ivert][iface]; + vertex_normal2[2][face_order2] = vertex_normal[2][ivert][iface]; + face_order2 = face_order2 + 1; + } + else { + edge_num_del = edge_num_del + 1; + } + + } + + face_order[iface] = face_order2; + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + face[ivert][iface] = face2[ivert]; + for ( j = 0; j < 3; j++ ) { + vertex_normal[j][ivert][iface] = vertex_normal2[j][ivert]; + } + } + + } + + printf ( "\n" ); + printf ( "EDGE_NULL_DELETE:\n" ); + printf ( " There are a total of %d edges.\n", edge_num ); + printf ( " Of these, %d were of zero length, and deleted.\n", edge_num_del ); + + return; +} +/**********************************************************************/ + +void face_area_set ( void ) + +/**********************************************************************/ + +/* + Purpose: + + FACE_AREA_SET computes the area of the faces. + + Formula: + + The area is the sum of the areas of the triangles formed by + node N with consecutive pairs of nodes. + + Reference: + + Adrian Bowyer and John Woodwark, + A Programmer's Geometry, + Butterworths, 1983. + + Modified: + + 17 July 1999 + + Author: + + John Burkardt +*/ +{ + float alpha; + float area_max; + float area_min; + float area_tri; + float base; + float dot; + float height; + int i; + int i1; + int i2; + int i3; + int iface; + int face_num_del; + float tol; + float x; + float x1; + float x2; + float x3; + float y; + float y1; + float y2; + float y3; + float z; + float z1; + float z2; + float z3; + + for ( iface = 0; iface < face_num; iface++ ) { + + face_area[iface] = 0.0; + + for ( i = 0; i < face_order[iface]-2; i++ ) { + + i1 = face[i][iface]; + i2 = face[i+1][iface]; + i3 = face[i+2][iface]; + + x1 = cor3[0][i1]; + y1 = cor3[1][i1]; + z1 = cor3[2][i1]; + + x2 = cor3[0][i2]; + y2 = cor3[1][i2]; + z2 = cor3[2][i2]; + + x3 = cor3[0][i3]; + y3 = cor3[1][i3]; + z3 = cor3[2][i3]; +/* + Find the projection of (P3-P1) onto (P2-P1). +*/ + dot = + ( x2 - x1 ) * ( x3 - x1 ) + + ( y2 - y1 ) * ( y3 - y1 ) + + ( z2 - z1 ) * ( z3 - z1 ); + + base = sqrt ( + ( x2 - x1 ) * ( x2 - x1 ) + + ( y2 - y1 ) * ( y2 - y1 ) + + ( z2 - z1 ) * ( z2 - z1 ) ); +/* + The height of the triangle is the length of (P3-P1) after its + projection onto (P2-P1) has been subtracted. +*/ + if ( base == 0.0 ) { + height = 0.0; + } + else { + + alpha = dot / ( base * base ); + + x = x3 - x1 - alpha * ( x2 - x1 ); + y = y3 - y1 - alpha * ( y2 - y1 ); + z = z3 - z1 - alpha * ( z2 - z1 ); + + height = sqrt ( x * x + y * y + z * z ); + + } + + area_tri = 0.5 * base * height; + + face_area[iface] = face_area[iface] + area_tri; + + } + + } + + area_min = face_area[0]; + area_max = face_area[0]; + + for ( iface = 1; iface < face_num; iface++ ) { + if ( area_min > face_area[iface] ) { + area_min = face_area[iface]; + } + if ( area_max < face_area[iface] ) { + area_max = face_area[iface]; + } + } + + printf ( "\n" ); + printf ( "FACE_AREA_SET:\n" ); + printf ( " Minimum face area is %f\n", area_min ); + printf ( " Maximum face area is %f\n", area_max ); + + tol = area_max / 10000.0; + + if ( area_min < tol ) { + + face_num_del = 0; + + for ( iface = 0; iface < face_num; iface++ ) { + if ( face_area[iface] < tol ) { + face_order[iface] = 0; + face_num_del = face_num_del + 1; + } + } + + printf ( " Marked %d tiny faces for deletion.\n", face_num_del ); + + } + + return; +} +/******************************************************************************/ + +void face_normal_ave ( void ) + +/******************************************************************************/ + +/* + Purpose: + + FACE_NORMAL_AVE sets face normals as average of face vertex normals. + + Modified: + + 09 October 1998 + + Author: + + John Burkardt +*/ +{ + int i; + int iface; + int ivert; + int nfix; + float norm; + float x; + float y; + float z; + + if ( face_num <= 0 ) { + return; + } + + nfix = 0; + + for ( iface = 0; iface < face_num; iface++ ) { + +/* + Check the norm of the current normal vector. +*/ + x = face_normal[0][iface]; + y = face_normal[1][iface]; + z = face_normal[2][iface]; + norm = ( float ) sqrt ( x * x + y * y + z * z ); + + if ( norm == 0.0 ) { + + nfix = nfix + 1; + + for ( i = 0; i < 3; i++ ) { + face_normal[i][iface] = 0.0; + } + + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + for ( i = 0; i < 3; i++ ) { + face_normal[i][iface] = face_normal[i][iface] + + vertex_normal[i][ivert][iface]; + } + } + + x = face_normal[0][iface]; + y = face_normal[1][iface]; + z = face_normal[2][iface]; + norm = ( float ) sqrt ( x * x + y * y + z * z ); + + if ( norm == 0.0 ) { + for ( i = 0; i < 3; i++ ) { + face_normal[i][iface] = ( float ) ( 1.0 / sqrt ( 3.0 ) ); + } + } + else { + for ( i = 0; i < 3; i++ ) { + face_normal[i][iface] = face_normal[i][iface] / norm; + } + } + } + } + + if ( nfix > 0 ) { + printf ( "\n" ); + printf ( "FACE_NORMAL_AVE: Recomputed %d face normals\n", nfix ); + printf ( " by averaging face vertex normals.\n" ); + } + return; +} +/**********************************************************************/ + +void face_null_delete ( void ) + +/**********************************************************************/ + +/* + Purpose: + + FACE_NULL_DELETE deletes faces of order less than 3. + + Comments: + + Thanks to Susan M. Fisher, University of North Carolina, + Department of Computer Science, for pointing out a coding error + in FACE_NULL_DELETE that was overwriting all the data! + + Modified: + + 30 November 1999 + + Author: + + John Burkardt +*/ +{ + int iface; + int ivert; + int j; + int face_num2; +/* + FACE_NUM2 is the number of faces we'll keep. +*/ + face_num2 = 0; +/* + Check every face. +*/ + for ( iface = 0; iface < face_num; iface++ ) { +/* + Keep it only if it has order 3 or more. +*/ + if ( face_order[iface] >= 3 ) { +/* + We don't have to slide data down in the array until + NUMFACE2 and IFACE get out of synch, that is, after + we've discarded at least one face. +*/ + if ( face_num2 != iface ) { + + face_area[face_num2] = face_area[iface]; + face_material[face_num2] = face_material[iface]; + face_order[face_num2] = face_order[iface]; + for ( ivert = 0; ivert < ORDER_MAX; ivert++ ) { + face[ivert][face_num2] = face[ivert][iface]; + vertex_material[ivert][face_num2] = vertex_material[ivert][iface]; + for ( j = 0; j < 3; j++ ) { + vertex_normal[j][ivert][face_num2] = vertex_normal[j][ivert][iface]; + } + } + + } +/* + Update the count only after we've used the un-incremented value + as a pointer. +*/ + face_num2 = face_num2 + 1; + + } + + } + + printf ( "\n" ); + printf ( "FACE_NULL_DELETE\n" ); + printf ( " There are a total of %d faces.\n", face_num ); + printf ( " Of these, %d passed the order test.\n", face_num2 ); + + face_num = face_num2; + + return; +} +/******************************************************************************/ + +int face_print ( int iface ) + +/******************************************************************************/ + +/* + Purpose: + + FACE_PRINT prints out information about a face. + + Modified: + + 31 August 1998 + + Author: + + John Burkardt +*/ +{ + int ivert; + int j; + int k; + + if ( iface < 0 || iface > face_num-1 ) { + printf ( "\n" ); + printf ( "FACE_PRINT - Fatal error!\n" ); + printf ( " Face indices must be between 1 and %d\n", face_num ); + printf ( " But your requested value was %d\n", iface ); + return ERROR; + } + + printf ( "\n" ); + printf ( "FACE_PRINT\n" ); + printf ( " Information about face %d\n", iface ); + printf ( "\n" ); + printf ( " Number of vertices is %d\n", face_order[iface] ); + printf ( "\n" ); + printf ( " Vertex list:\n" ); + printf ( " Vertex #, Node #, Material #, X, Y, Z:\n" ); + printf ( "\n" ); + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + j = face[ivert][iface]; + k = vertex_material[ivert][iface]; + printf ( " %d %d %d %f %f %f\n", ivert, j, k, cor3[0][j], cor3[1][j], + cor3[2][j] ); + } + + printf ( "\n" ); + printf ( " Face normal vector:\n" ); + printf ( "\n" ); + printf ( " %f %f %f\n", face_normal[0][iface], face_normal[1][iface], + face_normal[2][iface] ); + + printf ( "\n" ); + printf ( " Vertex face normals:\n" ); + printf ( "\n" ); + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + printf ( " %d %f %f %f\n", ivert, vertex_normal[0][ivert][iface], + vertex_normal[1][ivert][iface], vertex_normal[2][ivert][iface] ); + } + + return SUCCESS; + +} +/**********************************************************************/ + +void face_reverse_order ( void ) + +/**********************************************************************/ + +/* + Purpose: + + FACE_REVERSE_ORDER reverses the order of the nodes in each face. + + Discussion: + + Reversing the order of the nodes requires that the normal vectors + be reversed as well, so this routine will automatically reverse + the normals associated with nodes, vertices and faces. + + Modified: + + 28 June 1999 + + Author: + + John Burkardt +*/ +{ + int i; + int iface; + int itemp; + int ivert; + int j; + int m; + float temp; + + for ( iface = 0; iface < face_num; iface++ ) { + + m = face_order[iface]; + + for ( ivert = 0; ivert < ( m / 2 ); ivert++ ) { + + itemp = face[ivert][iface]; + face[ivert][iface] = face[m-1-ivert][iface]; + face[m-1-ivert][iface] = itemp; + + itemp = vertex_material[ivert][iface]; + vertex_material[ivert][iface] = vertex_material[m-1-ivert][iface]; + vertex_material[m-1-ivert][iface] = itemp; + + for ( j = 0; j < 3; j++ ) { + temp = vertex_normal[j][ivert][iface]; + vertex_normal[j][ivert][iface] = vertex_normal[j][m-1-ivert][iface]; + vertex_normal[j][m-1-ivert][iface] = temp; + } + + for ( j = 0; j < 2; j++ ) { + temp = vertex_tex_uv[j][ivert][iface]; + vertex_tex_uv[j][ivert][iface] = vertex_tex_uv[j][m-1-ivert][iface]; + vertex_tex_uv[j][m-1-ivert][iface] = temp; + } + + } + + } + + for ( i = 0; i < cor3_num; i++ ) { + for ( j = 0; j < 3; j++ ) { + cor3_normal[j][i] = - cor3_normal[j][i]; + } + } + + for ( i = 0; i < face_num; i++ ) { + for ( j = 0; j < 3; j++ ) { + face_normal[j][i] = - face_normal[j][i]; + } + } + + printf ( "\n" ); + printf ( "FACE_REVERSE_ORDER\n" ); + printf ( " Each list of nodes defining a face\n" ); + printf ( " has been reversed; related information,\n" ); + printf ( " including normal vectors, was also updated.\n" ); + + return; +} + +/******************************************************************************/ + +int face_subset ( void ) + +/******************************************************************************/ + +/* + Purpose: + + FACE_SUBSET selects a subset of the current faces as the new object. + + Warning: + + The original graphic object is overwritten by the new one. + + Modified: + + 12 October 1998 + + Author: + + John Burkardt + +*/ +{ + int i; + int iface; + int iface1; + int iface2; + int inc; + int ivert; + int j; + int k; + int cor3_num2; + + line_num = 0; +/* + Get the first and last faces to save, IFACE1 and IFACE2. +*/ + printf ( "\n" ); + printf ( "Enter lowest face number to save between 0 and %d:\n", face_num-1 ); + scanf ( "%d", &iface1 ); + if ( iface1 < 0 || iface1 > face_num - 1 ) { + printf ( "Illegal choice!\n" ); + return ERROR; + } + + printf ( "\n" ); + printf ( "Enter highest face number to save between %d and %d:\n", + iface1, face_num-1 ); + scanf ( "%d", &iface2 ); + if ( iface2 < iface1 || iface2 > face_num - 1 ) { + printf ( "Illegal choice!\n" ); + return ERROR; + } + + inc = iface1; +/* + "Slide" the data for the saved faces down the face arrays. +*/ + for ( iface = 0; iface < iface2 + 1 - iface1; iface++ ) { + face_order[iface] = face_order[iface+inc]; + for ( ivert = 0; ivert < ORDER_MAX; ivert++ ) { + face[ivert][iface] = face[ivert][iface+inc]; + vertex_material[ivert][iface] = vertex_material[ivert][iface+inc]; + for ( i = 0; i < 3; i++ ) { + vertex_normal[i][ivert][iface] = + vertex_normal[i][ivert][iface+inc]; + vertex_rgb[i][ivert][iface] = vertex_rgb[i][ivert][iface+inc]; + } + } + for ( i = 0; i < 3; i++ ) { + face_normal[i][iface] = face_normal[i][iface+inc]; + } + } +/* + Now reset the number of faces. +*/ + face_num = iface2 + 1 - iface1; +/* + Now, for each point I, set LIST(I) = J if point I is the J-th + point we are going to save, and 0 otherwise. Then J will be + the new label of point I. +*/ + for ( i = 0; i < cor3_num; i++ ) { + list[i] = -1; + } + + cor3_num2 = 0; + + for ( iface = 0; iface < face_num; iface++ ){ + for ( ivert = 0; ivert < face_order[iface]; ivert++ ){ + j = face[ivert][iface]; + if ( list[j] == -1 ) { + cor3_num2 = cor3_num2 + 1; + list[j] = cor3_num2; + } + } + } +/* + Now make the nonzero list entries rise in order, so that + we can compress the COR3 data in a minute. +*/ + cor3_num2 = 0; + + for ( i = 0; i < cor3_num; i++ ) { + if ( list[i] != -1 ) { + list[i] = cor3_num2; + cor3_num2 = cor3_num2 + 1; + } + } +/* + Relabel the FACE array with the new node indices. +*/ + for ( iface = 0; iface < face_num; iface++ ){ + for ( ivert = 0; ivert < face_order[iface]; ivert++ ){ + j = face[ivert][iface]; + face[ivert][iface] = list[j]; + } + } +/* + Rebuild the COR3 array by sliding data down. +*/ + for ( i = 0; i < cor3_num; i++ ){ + k = list[i]; + if ( k != -1 ) { + for ( j = 0; j < 3; j++ ) { + cor3[j][k] = cor3[j][i]; + } + } + } + + cor3_num = cor3_num2; + + return SUCCESS; +} +/**********************************************************************/ + +void face_to_line ( void ) + +/**********************************************************************/ + +/* + Purpose: + + FACE_TO_LINE converts face information to line information. + + Discussion: + + In some cases, the graphic information represented by polygonal faces + must be converted to a representation based solely on line segments. + This is particularly true if a VLA file is being written. + + Modified: + + 26 May 1999 + + Author: + + John Burkardt +*/ +{ + int icor3; + int iface; + int ivert; + int jcor3; + int jvert; +/* + Case 0: + No line pruning. +*/ + if ( line_prune == 0 ) { + + for ( iface = 0; iface < face_num; iface++ ) { + + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + + icor3 = face[ivert][iface]; + + line_num = line_num + 1; + if ( line_num <= LINES_MAX ) { + line_dex[line_num] = icor3; + line_material[line_num] = vertex_material[ivert][iface]; + } + } + + ivert = 0; + icor3 = face[ivert][iface]; + + line_num = line_num + 1; + if ( line_num <= LINES_MAX ) { + line_dex[line_num] = icor3; + line_material[line_num] = vertex_material[ivert][iface]; + } + + line_num = line_num + 1; + if ( line_num <= LINES_MAX ) { + line_dex[line_num] = -1; + line_material[line_num] = -1; + } + } + + } +/* + Case 2: + Simple-minded line pruning. + Only draw line (I,J) if I < J. +*/ + else { + + for ( iface = 0; iface < face_num; iface++ ) { + + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + + icor3 = face[ivert][iface]; + + if ( ivert + 1 < face_order[iface] ) { + jvert = ivert + 1; + } + else { + jvert = 0; + } + + jcor3 = face[jvert][iface]; + + if ( icor3 < jcor3 ) { + + if ( line_num + 3 < LINES_MAX ) { + + line_num = line_num + 1; + line_dex[line_num] = icor3; + line_material[line_num] = vertex_material[ivert][iface]; + + line_num = line_num + 1; + line_dex[line_num] = jcor3; + line_material[line_num] = vertex_material[jvert][iface]; + + line_num = line_num + 1; + line_dex[line_num] = -1; + line_material[line_num] = -1; + + } + } + } + } + + } + + return; +} +/**********************************************************************/ + +void face_to_vertex_material ( void ) + +/**********************************************************************/ + +/* + Purpose: + + FACE_TO_VERTEX_MAT extends face material definitions to vertices. + + Discussion: + + Assuming material indices are defined for all the faces, this + routine assigns to each vertex of a face the material of that face. + + Modified: + + 22 May 1999 + + Author: + + John Burkardt +*/ +{ + int iface; + int ivert; + + for ( iface = 0; iface < face_num; iface++ ) { + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + vertex_material[ivert][iface] = face_material[iface]; + } + } + + return; +} +/******************************************************************************/ + +char *file_ext ( char *file_name ) + +/******************************************************************************/ + +/* + Purpose: + + FILE_EXT picks out the extension in a file name. + + Modified: + + 21 July 1998 + + Author: + + John Burkardt +*/ +{ + int i; + + i = char_index_last ( file_name, '.' ); + + if ( i == -1 ) { + return NULL; + } + else { + return file_name + i + 1; + } +} +/******************************************************************************/ + +float float_read ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + FLOAT_READ reads 1 float from a binary file. + + Modified: + + 24 May 1999 +*/ +{ + float rval; + float temp; + + fread ( &temp, sizeof ( float ), 1, filein ); + + if ( byte_swap == TRUE ) { + rval = float_reverse_bytes ( temp ); + } + else { + rval = temp; + } + + return rval; +} +/******************************************************************************/ + +float float_reverse_bytes ( float x ) + +/******************************************************************************/ + +/* + Purpose: + + FLOAT_REVERSE_BYTES reverses the four bytes in a float. + + Modified: + + 24 May 1999 + + Author: + + John Burkardt + + Parameters: + + X, a float whose bytes are to be reversed. + + FLOAT_REVERSE_BYTES, a float with bytes in reverse order from those in X. +*/ +{ + char c; + union { + float yfloat; + char ychar[4]; + } y; + + y.yfloat = x; + + c = y.ychar[0]; + y.ychar[0] = y.ychar[3]; + y.ychar[3] = c; + + c = y.ychar[1]; + y.ychar[1] = y.ychar[2]; + y.ychar[2] = c; + + return ( y.yfloat ); +} +/******************************************************************************/ + +int float_write ( FILE *fileout, float float_val ) + +/******************************************************************************/ + +/* + Purpose: + + FLOAT_WRITE writes 1 float to a binary file. + + Modified: + + 23 September 1998 +*/ +{ + int nbyte = sizeof ( float ); + float temp; + + if ( byte_swap == TRUE ) { + temp = float_reverse_bytes ( float_val ); + } + else { + temp = float_val; + } + + fwrite ( &temp, nbyte, 1, fileout ); + + return nbyte; +} +/******************************************************************************/ + +int gmod_arch_check ( void ) + +/******************************************************************************/ + +/* + Purpose: + + GMOD_ARCH_CHECK inquires into some features of the computer architecture. + + Modified: + + 19 May 1999 + + Author: + + Zik Saleeba (zik@zikzak.net) +*/ +{ + static unsigned char one[4]; + int temp; + + temp = sizeof ( float ); + if ( temp != 4 ) { + return FALSE; + } + + *(float *)one = 1.0; + + if (one[0] == 0 && one[1] == 0 && one[2] == 128 && one[3] == 63) { + /* little endian IEEE floats */ + return TRUE; + } + + if (one[0] == 63 && one[1] == 128 && one[2] == 0 && one[3] == 0) { + /* big endian IEEE floats */ + return TRUE; + } + + return FALSE; +} +/******************************************************************************/ + +int gmod_read ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + GMOD_READ reads a golgotha GMOD file. + + Modified: + + 19 May 1999 + + Author: + + Zik Saleeba (zik@zikzak.net) +*/ + +/* +golgotha GMOD file format: + + + FILE HEADER + +w32 magic number f9 fa 63 1e +w32 number of sections +[ number of sections + w32 section id + w32 section offset +] + + + TEXTURE NAME SECTION - section id = 0x13 (19) + +w16 number of faces +[ number of faces + w16 texture name length + [ texture name length + w8 texture name character + ] +] + + + + MODEL QUADS SECTION - section id = 0x12 (18) + +w16 number of faces +[ number of faces + [ four vertices + w16 vertex index + float xpos (0.0-1.0) + float ypos (0.0-1.0) + ] + float scale + w16 flags + float xnormal (normal should be normalised) + float ynormal + float znormal +] + + + VERTEX ARRAY SECTION - section id = 0x14 (20) + +w16 number of vertices +w16 number of animations +w16 length of animation name +[ length of animation name + w8 animation name character +] +w16 number of frames in animation +[ number of frames in animation + [ number of vertices + float xpos + float ypos + float zpos + float xnormal + float ynormal + float znormal + ] +] +*/ +{ + unsigned char MagicNumber[4]; + unsigned long int NumSections; + int SectionCount; + unsigned long int SectionID[GMOD_MAX_SECTIONS]; + unsigned long int SectionOffset[GMOD_MAX_SECTIONS]; + + unsigned short NumAnimations; + unsigned short NumFrames; + unsigned short FaceCount; + unsigned short TextureCount; + int VertexCount; + + float Scale; + unsigned short Flags; + unsigned short TextureNameLen; + unsigned short AnimationNameLen; + int Order; + int MaxCor = 0; + + /* + * check if we can handle this architecture + */ + + if (!gmod_arch_check()) { + printf("GMOD_READ - This architecture not supported.\n"); + return ERROR; + } + + /* + * read the file header + */ + + /* read the magic number */ + fread(MagicNumber, 1, 4, filein); + if (MagicNumber[0] != 0xf9 || + MagicNumber[1] != 0xfa || + MagicNumber[2] != 0x63 || + MagicNumber[3] != 0x1e) { + printf("GMOD_READ - Bad magic number on GMOD file.\n"); + return ERROR; + } + + NumSections = gmod_read_w32(filein); + if (NumSections >= GMOD_MAX_SECTIONS) { + printf("GMOD_READ - Too many sections (%ld) in GMOD file - please increase static limit GMOD_MAX_SECTIONS\n", NumSections); + return ERROR; + } + +/* + Read the sections. +*/ + + for ( SectionCount = 0; SectionCount < ( int ) NumSections; SectionCount++ ) { + SectionID[SectionCount] = gmod_read_w32(filein); + SectionOffset[SectionCount] = gmod_read_w32(filein); + } +/* + Read each successive section. +*/ + for ( SectionCount = 0; SectionCount < ( int ) NumSections; SectionCount++ ) { +/* + Go to the start of the section. +*/ + fseek ( filein, ( long int ) SectionOffset[SectionCount], SEEK_SET ); +/* + What type of section is it? +*/ + switch (SectionID[SectionCount]) { + +/* + Model section. +*/ + case G1_SECTION_MODEL_QUADS: +/* + Get the number of faces. +*/ + face_num = gmod_read_w16 ( filein ); + + if (face_num > FACE_MAX) { + printf("GMOD_READ - Too many faces (%d) in GMOD file - please increase static limit FACE_MAX.\n", face_num); + return ERROR; + } +/* + Get the information on each face. +*/ + for ( FaceCount = 0; FaceCount < ( unsigned short ) face_num; FaceCount++ ) { + + Order = 0; + for ( VertexCount = 0; VertexCount < 4; VertexCount++ ) { + + /* read the vertex index */ + + face[VertexCount][FaceCount] = gmod_read_w16(filein); + + if (face[VertexCount][FaceCount] != GMOD_UNUSED_VERTEX) { + Order = VertexCount+1; + if (MaxCor < face[VertexCount][FaceCount]) + MaxCor = face[VertexCount][FaceCount]; + } + + /* read the texture position */ + + vertex_tex_uv[0][VertexCount][FaceCount] = gmod_read_float(filein); + vertex_tex_uv[1][VertexCount][FaceCount] = gmod_read_float(filein); + } + + /* scale and flags */ + + fread(&Scale, sizeof(Scale), 1, filein); + Flags = gmod_read_w16(filein); + + if ( debug ) { + printf ( "Flags = %d\n", Flags ); + } + + /* normal vector */ + + face_normal[0][FaceCount] = gmod_read_float(filein); + face_normal[1][FaceCount] = gmod_read_float(filein); + face_normal[2][FaceCount] = gmod_read_float(filein); + + /* the order is the number of used vertices */ + + face_order[FaceCount] = Order; + } + break; + + +/* + Texture name section. +*/ + + case G1_SECTION_MODEL_TEXTURE_NAMES: + + /* get the number of textures */ + + texture_num = gmod_read_w16(filein); + if (texture_num > TEXTURE_MAX) { + printf ( "GMOD_READ - Too many texture maps (%d) in GMOD file.\n", texture_num ); + printf ( " Increase static limit TEXTURE_MAX.\n" ); + return ERROR; + } + face_num = texture_num; + + for (TextureCount = 0; TextureCount < ( unsigned short ) texture_num; + TextureCount++) { + + /* read the texture name */ + + TextureNameLen = gmod_read_w16(filein); + fread ( texture_name[TextureCount], sizeof(char), TextureNameLen, filein); + texture_name[TextureCount][TextureNameLen] = '\0'; + } + break; + + + /* + * vertex section + */ + + case G1_SECTION_MODEL_VERT_ANIMATION: + + /* get the number of vertices */ + + cor3_num = gmod_read_w16(filein); + if (cor3_num > COR3_MAX) { + printf("GMOD_READ - Too many vertices (%d) in GMOD file - please increase static limit COR3_MAX.\n", cor3_num); + return ERROR; + } + +/* + Get the number of animations. +*/ + + NumAnimations = gmod_read_w16(filein); + + if (NumAnimations > 1) { + printf ( "GMOD_READ - Fatal error!\n" ); + printf ( " GMOD files can only handle one animation.\n" ); + printf ( " This file contains %d.\n", NumAnimations ); + return ERROR; + } + + /* read the animation name */ + AnimationNameLen = gmod_read_w16(filein); + fread ( anim_name, sizeof(char), AnimationNameLen, filein); + anim_name[AnimationNameLen] = '\0'; + + /* get the number of frames of animation */ + NumFrames = gmod_read_w16(filein); + if (NumFrames > 1) + printf("GMOD_READ - Too many frames of animation (%d) in GMOD file - will only use 1.\n", NumFrames); + + /* go through all the vertices, reading each one */ + for (VertexCount = 0; VertexCount < cor3_num; VertexCount++) { + + /* read the vertex */ + cor3[0][VertexCount] = gmod_read_float(filein); + cor3[1][VertexCount] = gmod_read_float(filein); + cor3[2][VertexCount] = gmod_read_float(filein); + + /* read the normal */ + cor3_normal[0][VertexCount] = gmod_read_float(filein); + cor3_normal[1][VertexCount] = gmod_read_float(filein); + cor3_normal[2][VertexCount] = gmod_read_float(filein); + } + break; + + default: + continue; + } + } + +/* + Set some other stray info. +*/ + line_num = 0; + +/* + Check for sanity. +*/ + if ( MaxCor >= cor3_num ) { + printf ( "GMOD_READ - Maximum coordinate index (%d)\n", MaxCor ); + printf ( " exceeded number of coordinates (%d) in GMOD file.\n", cor3_num ); + return ERROR; + } + + return SUCCESS; +} +/******************************************************************************/ + +float gmod_read_float ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + GMOD_READ_FLOAT reads a float from a Golgotha GMOD file. + + Modified: + + 19 May 1999 + + Author: + + Zik Saleeba (zik@zikzak.net) +*/ +{ + int endian = 1; + unsigned char *out_pos; + int i; + float Val; + + if (*(char *)&endian == 1) { + /* we're little-endian, which is native for GMOD floats */ + fread(&Val, sizeof(Val), 1, filein); + } + else { + /* we're big-endian, flip `em */ + out_pos = (unsigned char *)&Val; + for ( i = sizeof(Val)-1; i >= 0; i-- ) { + *(out_pos+i) = fgetc(filein); + } + } + + return Val; +} +/******************************************************************************/ + +unsigned short gmod_read_w16 ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + GMOD_READ_W16 reads a 16 bit word from a Golgotha GMOD file. + + Modified: + + 19 May 1999 + + Author: + + Zik Saleeba (zik@zikzak.net) +*/ +{ + unsigned char Byte1; + unsigned char Byte2; + + Byte1 = fgetc ( filein ); + Byte2 = fgetc ( filein ); + + return Byte1 | (((unsigned short)Byte2) << 8); +} +/******************************************************************************/ + +unsigned long gmod_read_w32 ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + GMOD_READ_W32 reads a 32 bit word from a Golgotha GMOD file. + + Modified: + + 19 May 1999 + + Author: + + Zik Saleeba (zik@zikzak.net) +*/ +{ + unsigned char Byte1, Byte2, Byte3, Byte4; + + Byte1 = fgetc(filein); + Byte2 = fgetc(filein); + Byte3 = fgetc(filein); + Byte4 = fgetc(filein); + + return Byte1 | + (((unsigned long)Byte2) << 8) | + (((unsigned long)Byte3) << 16) | + (((unsigned long)Byte4) << 24); +} + +/******************************************************************************/ + +int gmod_write ( FILE *fileout ) { + +/******************************************************************************/ + +/* + Purpose: + + GMOD_WRITE writes a Golgotha GMOD file. + + Modified: + + 19 May 1999 + + Author: + + Zik Saleeba (zik@zikzak.net) +*/ + static unsigned char MagicNumber[4] = { 0xf9, 0xfa, 0x63, 0x1e }; + unsigned long NumSections; + unsigned long SectionHeaderPos; + unsigned long TextureNameSectionPos; + unsigned long ModelSectionPos; + unsigned long VertexSectionPos; + + int VertexCount; + int FaceCount; + int TextureCount; + unsigned long SectionCount; + float Scale; + float Min[3]; + float Max[3]; + int CorNumber; + int DimensionCount; + float MaxWidth; +/* + Check if we can handle this architecture. +*/ + + if ( !gmod_arch_check() ) { + printf("GMOD_WRITE - This architecture not supported.\n"); + return ERROR; + } + +/* + Write the file header. +*/ + +/* + Write the magic number. +*/ + fwrite ( MagicNumber, sizeof(char), 4, fileout ); + +/* + Write the number of sections. +*/ + NumSections = 3; + gmod_write_w32 ( NumSections, fileout ); + +/* + Write a dummy section header which we'll overwrite later. +*/ + SectionHeaderPos = ftell ( fileout ); + for (SectionCount = 0; SectionCount < NumSections; SectionCount++) { + gmod_write_w32 ( 0, fileout ); + gmod_write_w32 ( 0, fileout ); + } +/* + Texture name section. +*/ + +/* + Take note of where we are in the file. +*/ + TextureNameSectionPos = ftell ( fileout ); + +/* + Write the number of textures. +*/ + + gmod_write_w16 ( ( unsigned short ) face_num, fileout ); +/* + Write the texture names. +*/ + for ( TextureCount = 0; TextureCount < face_num; TextureCount++ ) { + + gmod_write_w16 ( ( unsigned short ) strlen ( texture_name[TextureCount] ), + fileout ); + + fwrite ( texture_name[TextureCount], strlen ( texture_name[TextureCount] ), + 1, fileout ); + } + +/* + Model section. +*/ + +/* + Take note of where we are in the file. +*/ + + ModelSectionPos = ftell(fileout); + +/* + Write the number of faces. +*/ + + gmod_write_w16 ( ( unsigned short ) face_num, fileout ); + +/* + Write the information on each face. +*/ + + for ( FaceCount = 0; FaceCount < face_num; FaceCount++ ) { + + for (VertexCount = 0; VertexCount < ((face_order[FaceCount] < 4) ? face_order[FaceCount] : 4); VertexCount++) { + +/* + Write the vertex index. +*/ + gmod_write_w16 ( ( unsigned short ) face[VertexCount][FaceCount], fileout ); + +/* + Write the texture position. +*/ + + gmod_write_float ( vertex_tex_uv[0][VertexCount][FaceCount], fileout ); + gmod_write_float ( vertex_tex_uv[1][VertexCount][FaceCount], fileout ); + } + +/* + Write any extra vertices which are unused. +*/ + + for ( ; VertexCount < 4; VertexCount++ ) { + +/* + Write the vertex index. +*/ + gmod_write_w16 ( GMOD_UNUSED_VERTEX, fileout ); +/* + Write the texture position. +*/ + gmod_write_float ( vertex_tex_uv[0][VertexCount][FaceCount], fileout ); + + gmod_write_float ( vertex_tex_uv[1][VertexCount][FaceCount], fileout ); + } + +/* + Scale and flags. +*/ + +/* + Find the bounding box. +*/ + + for ( DimensionCount = 0; DimensionCount < 3; DimensionCount++ ) { + + CorNumber = face[0][FaceCount]; + Min[DimensionCount] = cor3[DimensionCount][CorNumber]; + Max[DimensionCount] = cor3[DimensionCount][CorNumber]; + + for (VertexCount = 1; VertexCount < ((face_order[FaceCount] < 4) ? face_order[FaceCount] : 4); VertexCount++) { + + CorNumber = face[VertexCount][FaceCount]; + + if (Min[DimensionCount] > cor3[DimensionCount][CorNumber]) + Min[DimensionCount] = cor3[DimensionCount][CorNumber]; + + if (Max[DimensionCount] < cor3[DimensionCount][CorNumber]) + Max[DimensionCount] = cor3[DimensionCount][CorNumber]; + } + } + +/* + The scale is the "width" of the face for mipmapping - + I just take the maximum bounding box dimension. +*/ + MaxWidth = Max[0] - Min[0]; + for ( DimensionCount = 1; DimensionCount < 3; DimensionCount++ ) { + + if ( MaxWidth < Max[DimensionCount] - Min[DimensionCount] ) + MaxWidth = Max[DimensionCount] - Min[DimensionCount]; + } + + Scale = MaxWidth; + fwrite ( &Scale, sizeof(Scale), 1, fileout ); + +/* + Flags are just nothing. +*/ + gmod_write_w16 ( 0, fileout ); +/* + Normal vector. +*/ + gmod_write_float ( face_normal[0][FaceCount], fileout ); + gmod_write_float ( face_normal[1][FaceCount], fileout ); + gmod_write_float ( face_normal[2][FaceCount], fileout ); + } + +/* + Vertex section. +*/ + +/* + Take note of where we are in the file. +*/ + + VertexSectionPos = ftell ( fileout ); + +/* + Write the number of vertices. +*/ + + gmod_write_w16 ( ( unsigned short ) cor3_num, fileout ); + +/* + Write the number of animations. +*/ + + gmod_write_w16 ( 1, fileout ); + +/* + Write the animation name. +*/ + + gmod_write_w16 ( 0, fileout ); + +/* + Write the number of frames of animation. +*/ + + gmod_write_w16 ( 1, fileout ); + +/* + Go through all the vertices, writing each one. +*/ + + for ( VertexCount = 0; VertexCount < cor3_num; VertexCount++ ) { + +/* + Write the vertex. +*/ + gmod_write_float ( cor3[0][VertexCount], fileout ); + gmod_write_float ( cor3[1][VertexCount], fileout ); + gmod_write_float ( cor3[2][VertexCount], fileout ); + +/* + Write the normal. +*/ + gmod_write_float ( cor3_normal[0][VertexCount], fileout ); + gmod_write_float ( cor3_normal[1][VertexCount], fileout ); + gmod_write_float ( cor3_normal[2][VertexCount], fileout ); + } +/* + Now rewrite the section header. +*/ + +/* + Go back to the section header. +*/ + fseek ( fileout, ( long int ) SectionHeaderPos, SEEK_SET ); + +/* + Write the texture name section header. +*/ + gmod_write_w32 ( G1_SECTION_MODEL_TEXTURE_NAMES, fileout ); + gmod_write_w32 ( TextureNameSectionPos, fileout ); + +/* + Write the model section header. +*/ + gmod_write_w32 ( G1_SECTION_MODEL_QUADS, fileout ); + gmod_write_w32 ( ModelSectionPos, fileout ); + +/* + Write the vertex section header. +*/ + gmod_write_w32 ( G1_SECTION_MODEL_VERT_ANIMATION, fileout ); + gmod_write_w32 ( VertexSectionPos, fileout ); + + return SUCCESS; +} + +/******************************************************************************/ + +void gmod_write_float ( float Val, FILE *fileout ) + +/******************************************************************************/ + +/* + Purpose: + + GMOD_WRITE_FLOAT writes a float to a Golgotha GMOD file. + + Modified: + + 19 May 1999 + + Author: + + Zik Saleeba (zik@zikzak.net) +*/ +{ + int endian = 1; + unsigned char *out_pos; + int i; + + if (*(char *)&endian == 1) { + /* we're little-endian, which is native for GMOD floats */ + fwrite ( &Val, sizeof(Val), 1, fileout ); + } + else { + /* we're big-endian, flip `em */ + out_pos = (unsigned char *)&Val; + for ( i = sizeof(Val)-1; i >= 0; i-- ) { + fputc(*(out_pos+i), fileout); + } + } +} +/******************************************************************************/ + +void gmod_write_w16 ( unsigned short Val, FILE *fileout ) + +/******************************************************************************/ + +/* + Purpose: + + GMOD_WRITE_W16 writes a 16 bit word to a Golgotha GMOD file. + + Modified: + + 13 September 2000 + + Author: + + Zik Saleeba (zik@zikzak.net) +*/ +{ + unsigned char OutByte[2]; + + OutByte[0] = (unsigned char)(Val & 0xff); + OutByte[1] = (unsigned char)(Val >> 8); + + fwrite ( OutByte, sizeof(unsigned char), 2, fileout ); +} +/******************************************************************************/ + +void gmod_write_w32 ( unsigned long Val, FILE *fileout ) + +/******************************************************************************/ + +/* + Purpose: + + GMOD_WRITE writes a 32 bit word to a Golgotha GMOD file. + + Modified: + + 19 May 1999 + + Author: + + Zik Saleeba (zik@zikzak.net) +*/ +{ + unsigned char OutByte[4]; + + OutByte[0] = (unsigned char)(Val & 0xff); + OutByte[1] = (unsigned char)((Val >> 8) & 0xff); + OutByte[2] = (unsigned char)((Val >> 16) & 0xff); + OutByte[3] = (unsigned char)((Val >> 24) & 0xff); + + fwrite ( OutByte, sizeof(unsigned char), 4, fileout ); +} + +/******************************************************************************/ + +void hello ( void ) + +/******************************************************************************/ +/* + Purpose: + + HELLO prints an explanatory header message. + + Modified: + + 04 July 2000 + + Author: + + John Burkardt +*/ +{ + printf ( "\n" ); + printf ( "Hello: This is IVCON,\n" ); + printf ( " for 3D graphics file conversion.\n" ); + printf ( "\n" ); + printf ( " \".3ds\" 3D Studio Max binary;\n" ); + printf ( " \".ase\" 3D Studio Max ASCII export;\n" ); + printf ( " \".byu\" Movie.BYU surface geometry;\n" ); + printf ( " \".dxf\" DXF;\n" ); + printf ( " \".gmod\" Golgotha model;\n" ); + printf ( " \".hrc\" SoftImage hierarchy;\n" ); + printf ( " \".iv\" SGI Open Inventor;\n" ); + printf ( " \".obj\" WaveFront Advanced Visualizer;\n" ); + printf ( " \".pov\" Persistence of Vision (output only);\n" ); + printf ( " \".smf\" Michael Garland's format;\n" ); + printf ( " \".stl\" ASCII StereoLithography;\n" ); + printf ( " \".stla\" ASCII StereoLithography;\n" ); + printf ( " \".stlb\" Binary StereoLithography;\n" ); + printf ( " \".tec\" TECPLOT (output only);\n" ); + printf ( " \".tri\" [Greg Hood ASCII triangle format];\n" ); + printf ( " \".tria\" [Greg Hood ASCII triangle format];\n" ); + printf ( " \".trib\" [Greg Hood binary triangle format];\n" ); + printf ( " \".txt\" Text (output only);\n" ); + printf ( " \".ucd\" AVS UCD file(output only);\n" ); + printf ( " \".vla\" VLA;\n" ); + printf ( " \".wrl\" VRML (Virtual Reality Modeling Language) (output only).\n" ); + printf ( " \".xgl\" XML/OpenGL format (output only);\n" ); + printf ( "\n" ); + printf ( " Current limits include:\n" ); + printf ( " %d faces;\n", FACE_MAX ); + printf ( " %d line items;\n", LINES_MAX ); + printf ( " %d points;\n", COR3_MAX ); + printf ( " %d face order;\n", ORDER_MAX ); + printf ( " %d materials;\n", MATERIAL_MAX); + printf ( " %d textures.\n", TEXTURE_MAX ); + printf ( "\n" ); + printf ( " Last modification: 04 July 2000.\n" ); + printf ( "\n" ); + printf ( " Send problem reports to burkardt@psc.edu.\n" ); + + return; +} +/******************************************************************************/ + +void help ( void ) + +/******************************************************************************/ + +/* + Purpose: + + HELP prints a list of the interactive commands. + + Modified: + + 26 May 1999 + + Author: + + John Burkardt +*/ +{ + printf ( "\n" ); + printf ( "Commands:\n" ); + printf ( "\n" ); + printf ( "< file Read data from input file;\n" ); + printf ( "<< file Append data in input file to current data;\n" ); + printf ( "> file Write output file;\n" ); + printf ( "B Switch the binary file byte-swapping mode;\n" ); + printf ( "D Switch the debugging mode;\n" ); + printf ( "F Print information about one face;\n" ); + printf ( "H Print this help list;\n" ); + printf ( "I Info, print out recent changes;\n" ); + printf ( "LINES Convert face information to lines;\n" ); + printf ( "N Recompute normal vectors;\n" ); + printf ( "P Set LINE_PRUNE option.\n" ); + printf ( "Q Quit;\n" ); + printf ( "R Reverse the normal vectors.\n" ); + printf ( "S Select face subset (NOT WORKING).\n" ); + printf ( "T Transform the data.\n" ); + printf ( "W Reverse the face node ordering.\n" ); + + return; +} +/******************************************************************************/ + +int hrc_read ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + HRC_READ reads graphics information from a SoftImage HRC file. + + Examples: + + HRCH: Softimage 4D Creative Environment v3.00 + + + model + { + name "cube_10x10" + scaling 1.000 1.000 1.000 + rotation 0.000 0.000 0.000 + translation 0.000 0.000 0.000 + + mesh + { + flag ( PROCESS ) + discontinuity 60.000 + + vertices 8 + { + [0] position -5.000 -5.000 -5.000 + [1] position -5.000 -5.000 5.000 + [2] position -5.000 5.000 -5.000 + [3] position -5.000 5.000 5.000 + [4] position 5.000 -5.000 -5.000 + [5] position 5.000 -5.000 5.000 + [6] position 5.000 5.000 -5.000 + [7] position 5.000 5.000 5.000 + } + + polygons 6 + { + [0] nodes 4 + { + [0] vertex 0 + normal -1.000 0.000 0.000 + uvTexture 0.000 0.000 + vertexColor 255 178 178 178 + [1] vertex 1 + normal -1.000 0.000 0.000 + uvTexture 0.000 0.000 + vertexColor 255 178 178 178 + [2] vertex 3 + normal -1.000 0.000 0.000 + uvTexture 0.000 0.000 + vertexColor 255 178 178 178 + [3] vertex 2 + normal -1.000 0.000 0.000 + uvTexture 0.000 0.000 + vertexColor 255 178 178 178 + } + material 0 + [1] nodes 4 + { + [0] vertex 1 + normal 0.000 0.000 1.000 + uvTexture 0.000 0.000 + vertexColor 255 178 178 178 + [1] vertex 5 + + ...etc..... + + [5] nodes 4 + { + [0] vertex 2 + normal 0.000 1.000 0.000 + uvTexture 0.000 0.000 + vertexColor 255 178 178 178 + [1] vertex 3 + normal 0.000 1.000 0.000 + uvTexture 0.000 0.000 + vertexColor 255 178 178 178 + [2] vertex 7 + normal 0.000 1.000 0.000 + uvTexture 0.000 0.000 + vertexColor 255 178 178 178 + [3] vertex 6 + normal 0.000 1.000 0.000 + uvTexture 0.000 0.000 + vertexColor 255 178 178 178 + } + material 0 + } + + edges 12 + { + [1] vertices 3 2 + [2] vertices 2 0 + [3] vertices 0 1 + [4] vertices 1 3 + [5] vertices 7 3 + [6] vertices 1 5 + [7] vertices 5 7 + [8] vertices 6 7 + [9] vertices 5 4 + [10] vertices 4 6 + [11] vertices 2 6 + [12] vertices 4 0 + } + } + + material [0] + { + name "kazoo" + type PHONG + ambient 0.0 1.0 0.0 + diffuse 1.0 0.0 0.0 + specular 0.0 0.0 1.0 + exponent 50.0 + reflectivity 0.0 + transparency 0.0 + refracIndex 1.0 + glow 0 + coc 0.0 + } + + texture [0] + { + name "/usr/users/foss/HOUSE/PICTURES/mellon" + glbname "t2d1" + anim STATIC + method XY + repeat 1 1 + scaling 1.000 1.000 + offset 0.000 0.000 + pixelInterp + effect INTENSITY + blending 1.000 + ambient 0.977 + diffuse 1.000 + specular 0.966 + reflect 0.000 + transp 0.000 + roughness 0.000 + reflMap 1.000 + rotation 0.000 + txtsup_rot 0.000 0.000 0.000 + txtsup_trans 0.000 0.000 0.000 + txtsup_scal 1.000 1.000 1.000 + } + } + + Modified: + + 25 June 1999 + + Author: + + John Burkardt +*/ +{ + float b; + int count; + float g; + int i; + int icor3; + int ivert; + int iword; + int jval; + int level; + char *next; + int nlbrack; + int nrbrack; + int cor3_num_old; + float r; + float t; + float temp[3]; + int width; + char word[LINE_MAX_LEN]; + char word1[LINE_MAX_LEN]; + char word2[LINE_MAX_LEN]; + char wordm1[LINE_MAX_LEN]; + float x; + float y; + float z; + + level = 0; + strcpy ( level_name[0], "Top" ); + nlbrack = 0; + nrbrack = 0; + cor3_num_old = cor3_num; + strcpy ( word, " " ); + strcpy ( wordm1, " " ); +/* + Read a line of text from the file. +*/ + for ( ;; ) { + + if ( fgets ( input, LINE_MAX_LEN, filein ) == NULL ) { + break; + } + + text_num = text_num + 1; + next = input; + iword = 0; +/* + Read a word from the line. +*/ + for ( ;; ) { + + strcpy ( wordm1, word ); + + count = sscanf ( next, "%s%n", word2, &width ); + next = next + width; + + if ( count <= 0 ) { + break; + } + + strcpy ( word, word2 ); + + iword = iword + 1; + + if ( iword == 1 ) { + strcpy ( word1, word ); + } +/* + The first line of the file must be the header. +*/ + if ( text_num == 1 ) { + + if ( strcmp ( word1, "HRCH:" ) != 0 ) { + printf ( "\n" ); + printf ( "HRC_READ - Fatal error!\n" ); + printf ( " The input file has a bad header.\n" ); + return ERROR; + } + else { + comment_num = comment_num + 1; + } + break; + } +/* + If the word is a curly bracket, count it. +*/ + if ( strcmp ( word, "{" ) == 0 ) { + nlbrack = nlbrack + 1; + level = nlbrack - nrbrack; + strcpy ( level_name[level], wordm1 ); + if ( debug ) { + printf ( "New level: %s\n", level_name[level] ); + } + } + else if ( strcmp ( word, "}" ) == 0 ) { + nrbrack = nrbrack + 1; + + if ( nlbrack < nrbrack ) { + printf ( "\n" ); + printf ( "HRC_READ - Fatal error!\n" ); + printf ( " Extraneous right bracket on line %d.\n", text_num ); + printf ( " Currently processing field %s\n.", level_name[level] ); + return ERROR; + } + } +/* + CONTROLPOINTS +*/ + if ( strcmp ( level_name[level], "controlpoints" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + + if ( line_num < LINES_MAX ) { + line_dex[line_num] = -1; + line_material[line_num] = 0; + } + line_num = line_num + 1; + level = nlbrack - nrbrack; + } + else if ( word[0] == '[' ) { + } + else if ( strcmp ( word, "position" ) == 0 ) { + + count = sscanf ( next, "%f%n", &x, &width ); + next = next + width; + + count = sscanf ( next, "%f%n", &y, &width ); + next = next + width; + + count = sscanf ( next, "%f%n", &z, &width ); + next = next + width; + + temp[0] = x; + temp[1] = y; + temp[2] = z; + + if ( cor3_num < 1000 ) { + icor3 = rcol_find ( cor3, 3, cor3_num, temp ); + } + else { + icor3 = -1; + } + + if ( icor3 == -1 ) { + + icor3 = cor3_num; + if ( cor3_num < COR3_MAX ) { + cor3[0][cor3_num] = x; + cor3[1][cor3_num] = y; + cor3[2][cor3_num] = z; + } + cor3_num = cor3_num + 1; + + } + else { + dup_num = dup_num + 1; + } + + if ( line_num < LINES_MAX ) { + line_dex[line_num] = icor3; + line_material[line_num] = 0; + } + line_num = line_num + 1; + } + else { + bad_num = bad_num + 1; + printf ( "CONTROLPOINTS: Bad data %s\n", word ); + return ERROR; + } + + } +/* + EDGES +*/ + else if ( strcmp ( level_name[level], "edges" ) == 0 ) { + + if ( strcmp( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( word[0] == '[' ) { + } + else if ( strcmp ( word, "vertices" ) == 0 ) { + + count = sscanf ( next, "%d%n", &jval, &width ); + next = next + width; + + if ( line_num < LINES_MAX ) { + line_dex[line_num] = jval + cor3_num_old; + line_material[line_num] = 0; + } + line_num = line_num + 1; + + count = sscanf ( next, "%d%n", &jval, &width ); + next = next + width; + + if ( line_num < LINES_MAX ) { + line_dex[line_num] = jval + cor3_num_old; + line_material[line_num] = 0; + } + line_num = line_num + 1; + + if ( line_num < LINES_MAX ) { + line_dex[line_num] = -1; + line_material[line_num] = -1; + } + line_num = line_num + 1; + + } + else { + bad_num = bad_num + 1; + printf ( "EDGES: Bad data %s\n", word ); + return ERROR; + } + + } +/* + MATERIAL +*/ + else if ( strcmp ( level_name[level], "material" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + material_num = material_num + 1; + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( word[0] == '[' ) { + } + else if ( strcmp ( word, "ambient" ) == 0 ) { + } + else if ( strcmp ( word, "coc" ) == 0 ) { + } + else if ( strcmp ( word, "diffuse" ) == 0 ) { + + count = sscanf ( next, "%f%n", &r, &width ); + next = next + width; + material_rgba[0][material_num-1] = r; + + count = sscanf ( next, "%f%n", &g, &width ); + next = next + width; + material_rgba[0][material_num-1] = g; + + count = sscanf ( next, "%f%n", &b, &width ); + next = next + width; + material_rgba[0][material_num-1] = b; + + } + else if ( strcmp ( word, "exponent" ) == 0 ) { + } + else if ( strcmp ( word, "glow" ) == 0 ) { + } + else if ( strcmp ( word, "name" ) == 0 ) { + count = sscanf ( next, "%s%n", word, &width ); + next = next + width; + strcpy ( material_name[material_num-1], word ); + } + else if ( strcmp ( word, "reflectivity" ) == 0 ) { + } + else if ( strcmp ( word, "refracindex" ) == 0 ) { + } + else if ( strcmp ( word, "specular" ) == 0 ) { + } + else if ( strcmp ( word, "transparency" ) == 0 ) { + count = sscanf ( next, "%f%n", &t, &width ); + next = next + width; + material_rgba[3][material_num-1] = 1.0 - t; + } + else if ( strcmp ( word, "type" ) == 0 ) { + } + else { + bad_num = bad_num + 1; + printf ( "MATERIAL: Bad data %s\n", word ); + return ERROR; + } + } +/* + MESH +*/ + else if ( strcmp ( level_name[level], "mesh" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( strcmp ( word, "discontinuity" ) == 0 ) { + break; + } + else if ( strcmp ( word, "edges" ) == 0 ) { + break; + } + else if ( strcmp ( word, "flag" ) == 0 ) { + break; + } + else if ( strcmp ( word, "polygons" ) == 0 ) { + break; + } + else if ( strcmp ( word, "vertices" ) == 0 ) { + break; + } + else { + bad_num = bad_num + 1; + printf ( "MESH: Bad data %s\n", word ); + return ERROR; + } + + } +/* + MODEL +*/ + else if ( strcmp ( level_name[level], "model" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( strcmp ( word, "material" ) == 0 ) { + break; + } + else if ( strcmp ( word, "mesh" ) == 0 ) { + break; + } + else if ( strcmp ( word, "name" ) == 0 ) { + break; + } + else if ( strcmp ( word, "patch" ) == 0 ) { + break; + } + else if ( strcmp ( word, "rotation" ) == 0 ) { + break; + } + else if ( strcmp ( word, "scaling" ) == 0 ) { + break; + } + else if ( strcmp ( word, "spline" ) == 0 ) { + break; + } + else if ( strcmp ( word, "translation" ) == 0 ) { + break; + } + else { + bad_num = bad_num + 1; + printf ( "MODEL: Bad data %s\n", word ); + return ERROR; + } + + } +/* + NODES +*/ + else if ( strcmp ( level_name[level], "nodes" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + ivert = 0; + face_order[face_num] = 0; + face_num = face_num + 1; + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( word[0] == '[' ) { + } + else if ( strcmp ( word, "normal" ) == 0 ) { + + count = sscanf ( next, "%f%n", &x, &width ); + next = next + width; + + count = sscanf ( next, "%f%n", &y, &width ); + next = next + width; + + count = sscanf ( next, "%f%n", &z, &width ); + next = next + width; + + if ( ivert < ORDER_MAX && face_num < FACE_MAX ) { + vertex_normal[0][ivert-1][face_num-1] = x; + vertex_normal[1][ivert-1][face_num-1] = y; + vertex_normal[2][ivert-1][face_num-1] = z; + } + + } + else if ( strcmp ( word, "uvTexture" ) == 0 ) { + + count = sscanf ( next, "%f%n", &x, &width ); + next = next + width; + + count = sscanf ( next, "%f%n", &y, &width ); + next = next + width; + + if ( ivert < ORDER_MAX && face_num < FACE_MAX ) { + vertex_tex_uv[0][ivert-1][face_num-1] = x; + vertex_tex_uv[1][ivert-1][face_num-1] = y; + } + } + else if ( strcmp ( word, "vertex" ) == 0 ) { + + count = sscanf ( next, "%d%n", &jval, &width ); + next = next + width; + + if ( ivert < ORDER_MAX && face_num < FACE_MAX ) { + face_order[face_num-1] = face_order[face_num-1] + 1; + face[ivert][face_num-1] = jval; + } + ivert = ivert + 1; + + } +/* + Right now, we don't do anything with the vertexColor information. +*/ + else if ( strcmp ( word, "vertexColor" ) == 0 ) { + + count = sscanf ( next, "%d%n", &jval, &width ); + next = next + width; + + count = sscanf ( next, "%d%n", &jval, &width ); + next = next + width; + + count = sscanf ( next, "%d%n", &jval, &width ); + next = next + width; + + count = sscanf ( next, "%d%n", &jval, &width ); + next = next + width; + } + else { + bad_num = bad_num + 1; + printf ( "NODES: Bad data %s\n", word ); + return ERROR; + } + + } +/* + PATCH + I don't know what to do with this yet. +*/ + else if ( strcmp ( level_name[level], "patch" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( strcmp ( word, "approx_type" ) == 0 ) { + } + else if ( strcmp ( word, "controlpoints" ) == 0 ) { + } + else if ( strcmp ( word, "curv_u" ) == 0 ) { + } + else if ( strcmp ( word, "curv_v" ) == 0 ) { + } + else if ( strcmp ( word, "recmin" ) == 0 ) { + } + else if ( strcmp ( word, "recmax" ) == 0 ) { + } + else if ( strcmp ( word, "recursion" ) == 0 ) { + } + else if ( strcmp ( word, "spacial" ) == 0 ) { + } + else if ( strcmp ( word, "taggedpoints" ) == 0 ) { + } + else if ( strcmp ( word, "ucurve" ) == 0 ) { + } + else if ( strcmp ( word, "ustep" ) == 0 ) { + } + else if ( strcmp ( word, "utension" ) == 0 ) { + } + else if ( strcmp ( word, "utype" ) == 0 ) { + } + else if ( strcmp ( word, "vclose" ) == 0 ) { + } + else if ( strcmp ( word, "vcurve" ) == 0 ) { + } + else if ( strcmp ( word, "viewdep" ) == 0 ) { + } + else if ( strcmp ( word, "vpoint" ) == 0 ) { + } + else if ( strcmp ( word, "vstep" ) == 0 ) { + } + else if ( strcmp ( word, "vtension" ) == 0 ) { + } + else if ( strcmp ( word, "vtype" ) == 0 ) { + } + else { + bad_num = bad_num + 1; + printf ( "PATCH: Bad data %s\n", word ); + return ERROR; + } + } +/* + POLYGONS +*/ + else if ( strcmp ( level_name[level], "polygons" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( word[0] == '[' ) { + } + else if ( strcmp ( word, "material" ) == 0 ) { + + count = sscanf ( next, "%d%n", &jval, &width ); + next = next + width; + + for ( ivert = 0; ivert < ORDER_MAX; ivert++ ) { + vertex_material[ivert][face_num-1] = jval; + } + + } + else if ( strcmp ( word, "nodes" ) == 0 ) { + count = sscanf ( next, "%s%n", word2, &width ); + next = next + width; + } + else { + bad_num = bad_num + 1; + printf ( "POLYGONS: Bad data %s\n", word ); + return ERROR; + } + + } +/* + SPLINE +*/ + else if ( strcmp ( level_name[level], "spline" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( strcmp ( word, "controlpoints" ) == 0 ) { + break; + } +/* + WHY DON'T YOU READ IN THE OBJECT NAME HERE? +*/ + else if ( strcmp ( word, "name" ) == 0 ) { + break; + } + else if ( strcmp ( word, "nbKeys" ) == 0 ) { + break; + } + else if ( strcmp ( word, "step" ) == 0 ) { + break; + } + else if ( strcmp ( word, "tension" ) == 0 ) { + break; + } + else if ( strcmp ( word, "type" ) == 0 ) { + break; + } + else { + bad_num = bad_num + 1; + printf ( "SPLINE: Bad data %s\n", word ); + return ERROR; + } + + } +/* + TAGGEDPOINTS +*/ + else if ( strcmp ( level_name[level], "taggedpoints" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( word[0] == '[' ) { + } + else if ( strcmp ( word, "tagged" ) == 0 ) { + } + else { + bad_num = bad_num + 1; + printf ( "TAGGEDPOINTS: Bad data %s\n", word ); + return ERROR; + } + + } +/* + TEXTURE +*/ + else if ( strcmp ( level_name[level], "texture" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + texture_num = texture_num + 1; + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( word[0] == '[' ) { + } + else if ( strcmp ( word, "ambient" ) == 0 ) { + } + else if ( strcmp ( word, "anim" ) == 0 ) { + } + else if ( strcmp ( word, "blending" ) == 0 ) { + } + else if ( strcmp ( word, "diffuse" ) == 0 ) { + } + else if ( strcmp ( word, "effect" ) == 0 ) { + } + else if ( strcmp ( word, "glbname" ) == 0 ) { + } + else if ( strcmp ( word, "method" ) == 0 ) { + } + else if ( strcmp ( word, "name" ) == 0 ) { + count = sscanf ( next, "%s%n", word, &width ); + next = next + width; + strcpy ( texture_name[texture_num-1], word ); + } + else if ( strcmp ( word, "offset" ) == 0 ) { + } + else if ( strcmp ( word, "pixelinterp" ) == 0 ) { + } + else if ( strcmp ( word, "reflect" ) == 0 ) { + } + else if ( strcmp ( word, "reflmap" ) == 0 ) { + } + else if ( strcmp ( word, "repeat" ) == 0 ) { + } + else if ( strcmp ( word, "rotation" ) == 0 ) { + } + else if ( strcmp ( word, "roughness" ) == 0 ) { + } + else if ( strcmp ( word, "scaling" ) == 0 ) { + } + else if ( strcmp ( word, "specular" ) == 0 ) { + } + else if ( strcmp ( word, "transp" ) == 0 ) { + } + else if ( strcmp ( word, "txtsup_rot" ) == 0 ) { + } + else if ( strcmp ( word, "txtsup_scal" ) == 0 ) { + } + else if ( strcmp ( word, "txtsup_trans" ) == 0 ) { + } + else { + bad_num = bad_num + 1; + printf ( "TEXTURE: Bad data %s\n", word ); + return ERROR; + } + } +/* + VERTICES +*/ + else if ( strcmp ( level_name[level], "vertices" ) == 0 ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( word[0] == '[' ) { + } + else if ( strcmp ( word, "position" ) == 0 ) { + + count = sscanf ( next, "%f%n", &x, &width ); + next = next + width; + + count = sscanf ( next, "%f%n", &y, &width ); + next = next + width; + + count = sscanf ( next, "%f%n", &z, &width ); + next = next + width; + + if ( cor3_num < COR3_MAX ) { + cor3[0][cor3_num] = x; + cor3[1][cor3_num] = y; + cor3[2][cor3_num] = z; + } + cor3_num = cor3_num + 1; + } + else { + bad_num = bad_num + 1; + printf ( "VERTICES: Bad data %s\n", word ); + return ERROR; + } + } +/* + Any other word: +*/ + else { + + } + } + } + +/* + End of information in file. + + Check the "materials" defining a line. + + If COORDINDEX is -1, so should be the MATERIALINDEX. + If COORDINDEX is not -1, then the MATERIALINDEX shouldn"t be either. +*/ + for ( i = 0; i < line_num; i++ ) { + + if ( line_dex[i] == -1 ) { + line_material[i] = -1; + } + else if ( line_material[i] == -1 ) { + line_material[i] = 0; + } + + } + return SUCCESS; +} +/******************************************************************************/ + +int hrc_write ( FILE* fileout ) + +/******************************************************************************/ + +/* + Purpose: + + HRC_WRITE writes graphics data to an HRC SoftImage file. + + Examples: + + HRCH: Softimage 4D Creative Environment v3.00 + + + model + { + name "cube_10x10" + scaling 1.000 1.000 1.000 + rotation 0.000 0.000 0.000 + translation 0.000 0.000 0.000 + + mesh + { + flag ( PROCESS ) + discontinuity 60.000 + + vertices 8 + { + [0] position -5.000 -5.000 -5.000 + [1] position -5.000 -5.000 5.000 + [2] position -5.000 5.000 -5.000 + [3] position -5.000 5.000 5.000 + [4] position 5.000 -5.000 -5.000 + [5] position 5.000 -5.000 5.000 + [6] position 5.000 5.000 -5.000 + [7] position 5.000 5.000 5.000 + } + + polygons 6 + { + [0] nodes 4 + { + [0] vertex 0 + normal -1.000 0.000 0.000 + uvTexture 0.000 0.000 + vertexColor 255 178 178 178 + [1] vertex 1 + normal -1.000 0.000 0.000 + uvTexture 0.000 0.000 + vertexColor 255 178 178 178 + [2] vertex 3 + normal -1.000 0.000 0.000 + uvTexture 0.000 0.000 + vertexColor 255 178 178 178 + [3] vertex 2 + normal -1.000 0.000 0.000 + uvTexture 0.000 0.000 + vertexColor 255 178 178 178 + } + material 0 + [1] nodes 4 + { + [0] vertex 1 + normal 0.000 0.000 1.000 + uvTexture 0.000 0.000 + vertexColor 255 178 178 178 + [1] vertex 5 + + ...etc..... + + [5] nodes 4 + { + [0] vertex 2 + normal 0.000 1.000 0.000 + uvTexture 0.000 0.000 + vertexColor 255 178 178 178 + [1] vertex 3 + normal 0.000 1.000 0.000 + uvTexture 0.000 0.000 + vertexColor 255 178 178 178 + [2] vertex 7 + normal 0.000 1.000 0.000 + uvTexture 0.000 0.000 + vertexColor 255 178 178 178 + [3] vertex 6 + normal 0.000 1.000 0.000 + uvTexture 0.000 0.000 + vertexColor 255 178 178 178 + } + material 0 + } + + edges 12 + { + [1] vertices 3 2 + [2] vertices 2 0 + [3] vertices 0 1 + [4] vertices 1 3 + [5] vertices 7 3 + [6] vertices 1 5 + [7] vertices 5 7 + [8] vertices 6 7 + [9] vertices 5 4 + [10] vertices 4 6 + [11] vertices 2 6 + [12] vertices 4 0 + } + } + + material [0] + { + name "kazoo" + type PHONG + ambient 0.0 1.0 0.0 + diffuse 1.0 0.0 0.0 + specular 0.0 0.0 1.0 + exponent 50.0 + reflectivity 0.0 + transparency 0.0 + refracIndex 1.0 + glow 0 + coc 0.0 + } + + texture [0] + { + name "/usr/users/foss/HOUSE/PICTURES/mellon" + glbname "t2d1" + anim STATIC + method XY + repeat 1 1 + scaling 1.000 1.000 + offset 0.000 0.000 + pixelInterp + effect INTENSITY + blending 1.000 + ambient 0.977 + diffuse 1.000 + specular 0.966 + reflect 0.000 + transp 0.000 + roughness 0.000 + reflMap 1.000 + rotation 0.000 + txtsup_rot 0.000 0.000 0.000 + txtsup_trans 0.000 0.000 0.000 + txtsup_scal 1.000 1.000 1.000 + } + } + + Modified: + + 25 June 1998 + + Author: + + John Burkardt + +*/ +{ + int iface; + int ivert; + int j; + int jhi; + int jlo; + int jrel; + int k; + int npts; + int nseg; + int text_num; + + nseg = 0; + text_num = 0; + + fprintf ( fileout, "HRCH: Softimage 4D Creative Environment v3.00\n" ); + fprintf ( fileout, "\n" ); + fprintf ( fileout, "\n" ); + text_num = text_num + 3; + + fprintf ( fileout, "model\n" ); + fprintf ( fileout, "{\n" ); + fprintf ( fileout, " name \"%s\"\n", object_name ); + fprintf ( fileout, " scaling 1.000 1.000 1.000\n" ); + fprintf ( fileout, " rotation 0.000 0.000 0.000\n" ); + fprintf ( fileout, " translation 0.000 0.000 0.000\n" ); + text_num = text_num + 6; + + if ( face_num > 0 ) { + + fprintf ( fileout, "\n" ); + fprintf ( fileout, " mesh\n" ); + fprintf ( fileout, " {\n" ); + fprintf ( fileout, " flag ( PROCESS )\n" ); + fprintf ( fileout, " discontinuity 60.000\n" ); + text_num = text_num + 5; +/* + Point coordinates. +*/ + if ( cor3_num > 0 ) { + + fprintf ( fileout, "\n" ); + fprintf ( fileout, " vertices %d\n", cor3_num ); + fprintf ( fileout, " {\n" ); + text_num = text_num + 3; + + for ( j = 0; j < cor3_num; j++ ) { + + fprintf ( fileout, " [%d] position %f %f %f\n", j, cor3[0][j], + cor3[1][j], cor3[2][j] ); + text_num = text_num + 1; + } + fprintf ( fileout, " }\n" ); + text_num = text_num + 1; + } +/* + Faces. +*/ + fprintf ( fileout, "\n" ); + fprintf ( fileout, " polygons %d\n", face_num ); + fprintf ( fileout, " {\n" ); + text_num = text_num + 3; + + for ( iface = 0; iface < face_num; iface++ ) { + + fprintf ( fileout, " [%d] nodes %d\n", iface, face_order[iface] ); + fprintf ( fileout, " {\n" ); + text_num = text_num + 2; + + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + + fprintf ( fileout, " [%d] vertex %d\n", ivert, face[ivert][iface] ); + fprintf ( fileout, " normal %f %f %f\n", + vertex_normal[0][ivert][iface], + vertex_normal[1][ivert][iface], vertex_normal[2][ivert][iface] ); + fprintf ( fileout, " uvTexture %f %f\n", + vertex_tex_uv[0][ivert][iface], vertex_tex_uv[1][ivert][iface] ); + fprintf ( fileout, " vertexColor 255 178 178 178\n" ); + text_num = text_num + 4; + } + fprintf ( fileout, " }\n" ); + fprintf ( fileout, " material %d\n", face_material[iface] ); + text_num = text_num + 2; + } + fprintf ( fileout, " }\n" ); + fprintf ( fileout, " }\n" ); + text_num = text_num + 2; + } +/* + IndexedLineSet. +*/ + if ( line_num > 0 ) { + + nseg = 0; + + jhi = -1; + + for ( ;; ) { + + jlo = jhi + 1; +/* + Look for the next index JLO that is not -1. +*/ + while ( jlo < line_num ) { + if ( line_dex[jlo] != -1 ) { + break; + } + jlo = jlo + 1; + } + + if ( jlo >= line_num ) { + break; + } +/* + Look for the highest following index JHI that is not -1. +*/ + jhi = jlo + 1; + + while ( jhi < line_num ) { + if ( line_dex[jhi] == -1 ) { + break; + } + jhi = jhi + 1; + } + + jhi = jhi - 1; +/* + Our next line segment involves LINE_DEX indices JLO through JHI. +*/ + nseg = nseg + 1; + npts = jhi + 1 - jlo; + + fprintf ( fileout, "\n" ); + fprintf ( fileout, " spline\n" ); + fprintf ( fileout, " {\n" ); + fprintf ( fileout, " name \"spl%d\"\n", nseg ); + fprintf ( fileout, " type LINEAR\n" ); + fprintf ( fileout, " nbKeys %d\n", npts ); + fprintf ( fileout, " tension 0.000\n" ); + fprintf ( fileout, " step 1\n" ); + fprintf ( fileout, "\n" ); + text_num = text_num + 9; + + fprintf ( fileout, " controlpoints\n" ); + fprintf ( fileout, " {\n" ); + text_num = text_num + 2; + + for ( j = jlo; j <= jhi; j++ ) { + jrel = j - jlo; + k = line_dex[j]; + fprintf ( fileout, " [%d] position %f %f %f\n", jrel, + cor3[0][k], cor3[1][k], cor3[2][k] ); + text_num = text_num + 1; + } + + fprintf ( fileout, " }\n" ); + fprintf ( fileout, " }\n" ); + text_num = text_num + 2; + } + } +/* + MATERIALS +*/ + for ( i = 0; i < material_num; i++ ) { + + fprintf ( fileout, " material [%d]\n", i ); + fprintf ( fileout, " {\n" ); + fprintf ( fileout, " name \"%s\"\n", material_name[i] ); + fprintf ( fileout, " type PHONG\n" ); + fprintf ( fileout, " ambient %f %f %f\n", material_rgba[0][i], + material_rgba[1][i], material_rgba[2][i] ); + fprintf ( fileout, " diffuse %f %f %f\n", material_rgba[0][i], + material_rgba[1][i], material_rgba[2][i] ); + fprintf ( fileout, " specular %f %f %f\n", material_rgba[0][i], + material_rgba[1][i], material_rgba[2][i] ); + fprintf ( fileout, " exponent 50.0\n" ); + fprintf ( fileout, " reflectivity 0.0\n" ); + fprintf ( fileout, " transparency %f\n", 1.0 - material_rgba[3][i] ); + fprintf ( fileout, " refracIndex 1.0\n" ); + fprintf ( fileout, " glow 0\n" ); + fprintf ( fileout, " coc 0.0\n" ); + fprintf ( fileout, " }\n" ); + + text_num = text_num + 14; + + } +/* + TEXTURES +*/ + for ( i = 0; i < texture_num; i++ ) { + + fprintf ( fileout, " texture [%d]\n", i ); + fprintf ( fileout, " {\n" ); + fprintf ( fileout, " name \"%s\"\n", texture_name[i] ); + fprintf ( fileout, " glbname \"t2d1\"\n" ); + fprintf ( fileout, " anim STATIC\n" ); + fprintf ( fileout, " method XY\n" ); + fprintf ( fileout, " repeat 1 1\n" ); + fprintf ( fileout, " scaling 1.000 1.000\n" ); + fprintf ( fileout, " offset 0.000 0.000\n" ); + fprintf ( fileout, " pixelInterp\n" ); + fprintf ( fileout, " effect INTENSITY\n" ); + fprintf ( fileout, " blending 1.000\n" ); + fprintf ( fileout, " ambient 0.977\n" ); + fprintf ( fileout, " diffuse 1.000\n" ); + fprintf ( fileout, " specular 0.966\n" ); + fprintf ( fileout, " reflect 0.000\n" ); + fprintf ( fileout, " transp 0.000\n" ); + fprintf ( fileout, " roughness 0.000\n" ); + fprintf ( fileout, " reflMap 1.000\n" ); + fprintf ( fileout, " rotation 0.000\n" ); + fprintf ( fileout, " txtsup_rot 0.000 0.000 0.000\n" ); + fprintf ( fileout, " txtsup_trans 0.000 0.000 0.000\n" ); + fprintf ( fileout, " txtsup_scal 1.000 1.000 1.000\n" ); + fprintf ( fileout, " }\n" ); + + text_num = text_num + 25; + + } + fprintf ( fileout, "}\n" ); + text_num = text_num + 1; +/* + Report. +*/ + printf ( "\n" ); + printf ( "HRC_WRITE - Wrote %d text lines.\n", text_num ); + + return SUCCESS; +} +/******************************************************************************/ + +void init_program_data ( void ) + +/******************************************************************************/ + +/* + Purpose: + + INIT_PROGRAM_DATA initializes the internal program data. + + Modified: + + 26 May 1999 + + Author: + + John Burkardt +*/ +{ + byte_swap = FALSE; + debug = 0; + line_prune = 1; + color_num = 0; + cor3_num = 0; + face_num = 0; + line_num = 0; + + if ( debug ) { + printf ( "\n" ); + printf ( "INIT_PROGRAM_DATA: Program data initialized.\n" ); + } + + return; + +} +/******************************************************************************/ + +int interact ( void ) + +/******************************************************************************/ + +/* + Purpose: + + INTERACT carries on an interactive session with the user. + + Modified: + + 22 May 1999 + + Author: + + John Burkardt +*/ +{ + int i; + int icor3; + int ierror; + int iface; + int itemp; + int ivert; + int j; + int jvert; + int m; + char *next; + float temp; + float x; + float y; + float z; + + strcpy ( filein_name, "NO_IN_NAME" ); + strcpy ( fileout_name, "NO_OUT_NAME" ); + +/* + Say hello. +*/ + hello ( ); +/* + Get the next user command. +*/ + printf ( "\n" ); + printf ( "Enter command (H for help)\n" ); + + while ( fgets ( input, LINE_MAX_LEN, stdin ) != NULL ) { +/* + Advance to the first nonspace character in INPUT. +*/ + for ( next = input; *next != '\0' && isspace(*next); next++ ) { + } +/* + Skip blank lines and comments. +*/ + if ( *next == '\0' ) { + continue; + } +/* + Command: << FILENAME + Append new data to current graphics information. +*/ + if ( *next == '<' && *(next+1) == '<' ) { + + next = next + 2; + sscanf ( next, "%s", filein_name ); + + ierror = data_read ( ); + + if ( ierror == ERROR ) { + printf ( "\n" ); + printf ( "INTERACT - Fatal error!\n" ); + printf ( " DATA_READ failed to read input data.\n" ); + } + } +/* + Command: < FILENAME +*/ + else if ( *next == '<' ) { + + next = next + 1; + sscanf ( next, "%s", filein_name ); + + data_init ( ); + + ierror = data_read ( ); + + if ( ierror == ERROR ) { + printf ( "\n" ); + printf ( "INTERACT - Fatal error!\n" ); + printf ( " DATA_READ failed to read input data.\n" ); + } + } +/* + Command: > FILENAME +*/ + else if ( *next == '>' ) { + + next = next + 1; + sscanf ( next, "%s", fileout_name ); + + ierror = data_write ( ); + + if ( ierror == ERROR ) { + printf ( "\n" ); + printf ( "INTERACT - Fatal error!\n" ); + printf ( " OUTPUT_DATA failed to write output data.\n" ); + } + + } +/* + B: Switch byte swapping option. +*/ + else if ( *next == 'B' || *next == 'b' ) { + + if ( byte_swap == TRUE ) { + byte_swap = FALSE; + printf ( "Byte_swapping reset to FALSE.\n" ); + } + else { + byte_swap = TRUE; + printf ( "Byte_swapping reset to TRUE.\n" ); + } + + } +/* + D: Switch debug option. +*/ + else if ( *next == 'D' || *next == 'd' ) { + if ( debug ) { + debug = 0; + printf ( "Debug reset to FALSE.\n" ); + } + else { + debug = 1; + printf ( "Debug reset to TRUE.\n" ); + } + } +/* + F: Check a face. +*/ + else if ( *next == 'f' || *next == 'F' ) { + printf ( "\n" ); + printf ( " Enter a face index between 0 and %d:", face_num-1 ); + scanf ( "%d", &iface ); + face_print ( iface ); + } +/* + H: Help +*/ + else if ( *next == 'h' || *next == 'H' ) { + help ( ); + } +/* + I: Print change information. +*/ + else if ( *next == 'i' || *next == 'I') { + news ( ); + } +/* + LINES: + Convert face information to lines. +*/ + else if ( *next == 'l' || *next == 'L') { + + if ( face_num > 0 ) { + + printf ( "\n" ); + printf ( "INTERACT - Note:\n" ); + printf ( " Face information will be converted\n" ); + printf ( " to line information.\n" ); + + face_to_line ( ); + + if ( line_num > LINES_MAX ) { + + printf ( "\n" ); + printf ( "INTERACT - Note:\n" ); + printf ( " Some face information was lost.\n" ); + printf ( " The maximum number of lines is %d,\n", LINES_MAX ); + printf ( " but we would need at least %d.\n", line_num ); + + line_num = LINES_MAX; + + } + + face_num = 0; + } + else { + + printf ( "\n" ); + printf ( "INTERACT - Note:\n" ); + printf ( " There were no faces to convert.\n" ); + + } + + } +/* + N: Recompute normal vectors. +*/ + else if ( *next == 'n' || *next == 'N') { + + for ( iface = 0; iface < face_num; iface++ ) { + for ( i = 0; i < 3; i++ ) { + face_normal[i][iface] = 0.0; + } + } + + for ( iface = 0; iface < face_num; iface++ ) { + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + for ( i = 0; i < 3; i++ ) { + vertex_normal[i][ivert][iface] = 0.0; + } + } + } + + vertex_normal_set ( ); + + cor3_normal_set ( ); + + face_normal_ave ( ); + } +/* + P: Line pruning optiont +*/ + else if ( *next == 'p' || *next == 'P' ) { + + printf ( "\n" ); + printf ( "INTERACT - SET LINE PRUNING OPTION.\n" ); + printf ( "\n" ); + printf ( " LINE_PRUNE = 0 means no line pruning.\n" ); + printf ( " nonzero means line pruning.\n" ); + printf ( "\n" ); + printf ( " Current value is LINE_PRUNE = %d.\n", line_prune ); + printf ( "\n" ); + printf ( " Enter new value for LINE_PRUNE.\n" ); + + if ( fgets ( input, LINE_MAX_LEN, stdin ) == NULL ) { + printf ( " ??? Error trying to read input.\n" ); + } + else { + sscanf ( input, "%d", &line_prune ); + printf ( " New value is LINE_PRUNE = %d.\n", line_prune ); + } + } +/* + Q: Quit +*/ + else if ( *next == 'q' || *next == 'Q' ) { + printf ( "\n" ); + printf ( "INTERACT - Normal end of execution.\n" ); + return SUCCESS; + } +/* + R: Reverse normal vectors. +*/ + else if ( *next == 'r' || *next == 'R' ) { + + for ( icor3 = 0; icor3 < cor3_num; icor3++ ) { + for ( i = 0; i < 3; i++ ) { + cor3_normal[i][icor3] = - cor3_normal[i][icor3]; + } + } + + for ( iface = 0; iface < face_num; iface++ ) { + for ( i = 0; i < 3; i++ ) { + face_normal[i][iface] = - face_normal[i][iface]; + } + } + + for ( iface = 0; iface < face_num; iface++ ) { + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + for ( i = 0; i < 3; i++ ) { + vertex_normal[i][ivert][iface] = + - vertex_normal[i][ivert][iface]; + } + } + } + printf ( "\n" ); + printf ( "INTERACT - Note:\n" ); + printf ( " Reversed node, face and vertex normals.\n" ); + } +/* + S: Select a few faces, discard the rest. +*/ + else if ( *next == 's' || *next == 'S' ) { + face_subset ( ); + } +/* + T: Transform the data. +*/ + else if ( *next == 't' || *next == 'T' ) { + + printf ( "\n" ); + printf ( "For now, we only offer point scaling.\n" ); + printf ( "Enter X, Y, Z scale factors:\n" ); + + scanf ( "%f %f %f", &x, &y, &z ); + + for ( j = 0; j < cor3_num; j++ ) { + cor3[0][j] = x * cor3[0][j]; + cor3[1][j] = y * cor3[1][j]; + cor3[2][j] = z * cor3[2][j]; + } + + for ( iface = 0; iface < face_num; iface++ ) { + for ( i = 0; i < 3; i++ ) { + face_normal[i][iface] = 0.0; + } + } + + for ( iface = 0; iface < face_num; iface++ ) { + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + for ( i = 0; i < 3; i++ ) { + vertex_normal[i][ivert][iface] = 0.0; + } + } + } + + vertex_normal_set ( ); + + cor3_normal_set ( ); + + face_normal_ave ( ); + } +/* + U: Renumber faces, count objects: +*/ + else if ( *next == 'u' || *next == 'U' ) { + } +/* + V: Convert polygons to triangles: +*/ + else if ( *next == 'v' || *next == 'V' ) { + } +/* + W: Reverse the face node ordering. +*/ + else if ( *next == 'w' || *next == 'W' ) { + + if ( face_num > 0 ) { + + for ( iface = 0; iface < face_num; iface++ ) { + + m = face_order[iface]; + + for ( ivert = 0; ivert < m/2; ivert++ ) { + + jvert = m - ivert - 1; + + itemp = face[ivert][iface]; + face[ivert][iface] = face[jvert][iface]; + face[jvert][iface] = itemp; + + itemp = vertex_material[ivert][iface]; + vertex_material[ivert][iface] = vertex_material[jvert][iface]; + vertex_material[jvert][iface] = itemp; + + for ( i = 0; i < 3; i++ ) { + temp = vertex_normal[i][ivert][iface]; + vertex_normal[i][ivert][iface] = + vertex_normal[i][jvert][iface]; + vertex_normal[i][jvert][iface] = temp; + } + } + } + printf ( "\n" ); + printf ( "INTERACT - Note:\n" ); + printf ( " Reversed face node ordering.\n" ); + } + } +/* + Command: ??? +*/ + else { + printf ( "\n" ); + printf ( "INTERACT: Warning!\n" ); + printf ( " Your command was not recognized.\n" ); + } + + printf ( "\n" ); + printf ( "Enter command (H for help)\n" ); + + } + return SUCCESS; +} +/******************************************************************************/ + +int iv_read ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + IV_READ reads graphics information from an Inventor file. + + Example: + + #Inventor V2.0 ascii + + Separator { + Info { + string "Inventor file generated by IVCON. + Original data in file cube.iv." + } + Separator { + LightModel { + model PHONG + } + MatrixTransform { matrix + 0.9 0.0 0.0 0.0 + 0.0 -0.9 0.0 0.0 + 0.0 0.0 -1.5 0.0 + 0.0 0.0 0.0 1.0 + } + Material { + ambientColor 0.2 0.2 0.2 + diffuseColor [ + 0.8 0.8 0.8, + 0.7 0.1 0.1, + 0.1 0.8 0.2, + ] + emissiveColor 0.0 0.0 0.0 + specularColor 0.0 0.0 0.0 + shininess 0.2 + transparency [ + 0.0, 0.5, 1.0, + ] + } + Texture2 { + filename "fred.rgb" + wrapS REPEAT + wrapT REPEAT + model MODULATE + blendColor 0.0 0.0 0.0 + } + + MaterialBinding { + value PER_VERTEX_INDEXED + } + NormalBinding { + value PER_VERTEX_INDEXED + } + TextureCoordinateBinding { + value PER_VERTEX_INDEXED + } + + ShapeHints { + vertexOrdering COUNTERCLOCKWISE + shapeType UNKNOWN_SHAPE_TYPE + faceType CONVEX + creaseAngle 6.28319 + } + + Coordinate3 { + point [ + 8.59816 5.55317 -3.05561, + 8.59816 2.49756 0.000000E+00, + ...etc... + 2.48695 2.49756 -3.05561, + ] + } + + Normal { + vector [ + 0.71 0.71 0.0, + ...etc... + 0.32 0.32 0.41, + ] + } + + TextureCoordinate2 { + point [ + 0.0 1.0, + 0.1, 0.8, + ...etc... + 0.4 0.7, + ] + } + + IndexedLineSet { + coordIndex [ + 0, 1, 2, -1, + 3, 4, 5, -1, + 7, 8, 9, -1, + ...etc... + 189, 190, 191, -1, + ] + materialIndex [ + 0, 0, 0, -1, + 1, 1, 1, -1, + 2, 2, 2, -1, + ...etc... + 64, 64, 64, -1, + ] + } + + IndexedFaceSet { + coordIndex [ + 0, 1, 2, -1, + 3, 4, 5, -1, + 7, 8, 9, -1, + ...etc... + 189, 190, 191, -1, + ] + materialIndex [ + 0, 0, 0, -1, + 1, 1, 1, -1, + 2, 2, 2, -1, + ...etc... + 64, 64, 64, -1, + ] + normalIndex [ + 0, 0, 0, -1, + 1, 1, 1, -1, + 2, 2, 2, -1, + ...etc... + 64, 64, 64, -1, + ] + textureCoordIndex [ + 0, 0, 0, -1, + 1, 1, 1, -1, + 2, 2, 2, -1, + ...etc... + 64, 64, 64, -1, + ] + } + + IndexedTriangleStripSet { + vertexProperty VertexProperty { + vertex [ x y z, + ... + x y z ] + normal [ x y z, + ... + x y z ] + materialBinding OVERALL + normalBinding PER_VERTEX_INDEXED + } + coordIndex [ + i, j, k, l, m, -1, + n, o, p, q, r, s, t, u, -1, + v, w, x, -1 + ..., -1 ] + normalIndex -1 + } + + } + } + + Modified: + + 01 July 1999 + + Author: + + John Burkardt +*/ +{ + char c; + int count; + int i; + int icol; + int icolor; + int icface; + int inormface; + int iface_num; + int irow; + int iuv; + int ivert; + int iword; + int ix; + int ixyz; + int iy; + int iz; + int j; + int jval; + int level; + char *next; + int nlbrack; + int nrbrack; + int nu; + int null_index; + int cor3_num_old; + int line_num2; + int face_num2; + int normal_num_temp; + int text_numure_temp; + int nv; + int result; + float rval; + int width; + char word[LINE_MAX_LEN]; + char word1[LINE_MAX_LEN]; + char wordm1[LINE_MAX_LEN]; + float xvec[3]; + + icface = 0; + icol = -1; + inormface = 0; + iface_num = face_num; + irow = 0; + ix = 0; + ixyz = 0; + iy = 0; + iz = 0; + jval = 0; + level = 0; + strcpy ( level_name[0], "Top" ); + nlbrack = 0; + nrbrack = 0; + nu = 0; + cor3_num_old = cor3_num; + face_num2 = face_num; + line_num2 = line_num; + normal_num_temp = 0; + text_numure_temp = 0; + nv = 0; + rval = 0.0; + strcpy ( word, " " ); + strcpy ( wordm1, " " ); +/* + Read the next line of text from the input file. +*/ + for ( ;; ) { + + if ( fgets ( input, LINE_MAX_LEN, filein ) == NULL ) { + break; + } + + text_num = text_num + 1; + next = input; + iword = 0; +/* + Remove all commas from the line, so we can use SSCANF to read + numeric items. +*/ + i = 0; + while ( input[i] != '\0' ) { + if ( input[i] == ',' ) { + input[i] = ' '; + } + i++; + } +/* + Force brackets and braces to be buffered by spaces. +*/ + i = 0; + while ( input[i] != '\0' ) { + i++; + } + null_index = i; + + i = 0; + while ( input[i] != '\0' && i < LINE_MAX_LEN ) { + + if ( input[i] == '[' || input[i] == ']' || + input[i] == '{' || input[i] == '}' ) { + + result = char_pad ( &i, &null_index, input, LINE_MAX_LEN ); + if ( result == ERROR ) { + break; + } + } + else { + i++; + } + } +/* + Read a word from the line. +*/ + for ( ;; ) { + + strcpy ( wordm1, word ); + strcpy ( word, " " ); + + count = sscanf ( next, "%s%n", word, &width ); + next = next + width; + + if ( count <= 0 ) { + break; + } + + iword = iword + 1; + + if ( iword == 1 ) { + strcpy ( word1, word ); + } +/* + The first line of the file must be the header. +*/ + if ( text_num == 1 ) { + + if ( leqi ( word1, "#Inventor" ) != TRUE ) { + printf ( "\n" ); + printf ( "IV_READ - Fatal error!\n" ); + printf ( " The input file has a bad header.\n" ); + return ERROR; + } + else { + comment_num = comment_num + 1; + } + break; + } +/* + A comment begins anywhere with '#'. + Skip the rest of the line. +*/ + if ( word[1] == '#' ) { + comment_num = comment_num + 1; + break; + } +/* + If the word is a curly or square bracket, count it. + If the word is a left bracket, the previous word is the name of a node. +*/ + if ( strcmp ( word, "{" ) == 0 || strcmp ( word, "[" ) == 0 ) { + nlbrack = nlbrack + 1; + level = nlbrack - nrbrack; + strcpy ( level_name[level], wordm1 ); + if ( debug ) { + printf ( "Begin level: %s\n", wordm1 ); + } + } + else if ( strcmp ( word, "}" ) == 0 || strcmp ( word, "]" ) == 0 ) { + nrbrack = nrbrack + 1; + + if ( nlbrack < nrbrack ) { + printf ( "\n" ); + printf ( "IV_READ - Fatal error!\n" ); + printf ( " Extraneous right bracket on line %d.\n", text_num ); + printf ( " Currently processing field %s\n.", level_name[level] ); + return ERROR; + } + } +/* + BASECOLOR +*/ + if ( leqi ( level_name[level], "BASECOLOR" ) == TRUE ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( leqi ( word, "RGB" ) == TRUE ) { + } + else { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } +/* + COORDINATE3 +*/ + else if ( leqi ( level_name[level], "COORDINATE3" ) == TRUE ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( leqi ( word, "POINT" ) == TRUE ) { + } + else { + bad_num = bad_num + 1; + printf ( "COORDINATE3: Bad data %s\n", word ); + } + } +/* + COORDINATE4 +*/ + else if ( leqi ( level_name[level], "COORDINATE4" ) == TRUE ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( leqi ( word, "POINT" ) == TRUE ) { + } + else { + bad_num = bad_num + 1; + printf ( "COORDINATE4: Bad data %s\n", word ); + } + } +/* + COORDINDEX +*/ + else if ( leqi ( level_name[level], "COORDINDEX" ) == TRUE ) { + + if ( strcmp ( word, "[" ) == 0 ) { + ivert = 0; + } + else if ( strcmp ( word, "]" ) == 0 ) { + level = nlbrack - nrbrack; + } +/* + (indexedlineset) COORDINDEX +*/ + else if ( leqi ( level_name[level-1], "INDEXEDLINESET" ) == TRUE ) { + + count = sscanf ( word, "%d%n", &jval, &width ); + + if ( count > 0 ) { + + if ( jval < -1 ) { + bad_num = bad_num + 1; + } + else { + if ( line_num < LINES_MAX ) { + if ( jval != -1 ) { + jval = jval + cor3_num_old; + } + line_dex[line_num] = jval; + } + line_num = line_num + 1; + } + } + else { + bad_num = bad_num + 1; + } + } +/* + (indexedfaceset) COORDINDEX + Warning: If the list of indices is not terminated with a final -1, then + the last face won't get counted. +*/ + else if ( leqi ( level_name[level-1], "INDEXEDFACESET" ) == TRUE ) { + + count = sscanf ( word, "%d%n", &jval, &width ); + + if ( count > 0 ) { + if ( jval == -1 ) { + ivert = 0; + face_num = face_num + 1; + } + else { + if ( ivert == 0 ) { + if ( face_num < FACE_MAX ) { + face_order[face_num] = 0; + } + } + if ( face_num < FACE_MAX ) { + face_order[face_num] = face_order[face_num] + 1; + face[ivert][face_num] = jval + cor3_num_old; + ivert = ivert + 1; + } + } + } + } +/* + (indexednurbssurface) COORDINDEX +*/ + else if ( leqi ( level_name[level-1], "INDEXEDNURBSSURFACE" ) == TRUE ) { + } +/* + (indexedtrianglestripset) COORDINDEX + + First three coordinate indices I1, I2, I3 define a triangle. + Next triangle is defined by I2, I3, I4 (actually, I4, I3, I2 + to stay with same counterclockwise sense). + Next triangle is defined by I3, I4, I5 ( do not need to reverse + odd numbered triangles) and so on. + List is terminated with -1. +*/ + else if ( leqi ( level_name[level-1], "INDEXEDTRIANGLESTRIPSET" ) == TRUE ) { + + count = sscanf ( word, "%d%n", &jval, &width ); + + if ( count > 0 ) { + + if ( jval == -1 ) { + ivert = 0; + } + else { + + ix = iy; + iy = iz; + iz = jval + cor3_num_old; + + if ( ivert == 0 ) { + if ( face_num < FACE_MAX ) { + face[ivert][face_num] = jval + cor3_num_old; + face_order[face_num] = 3; + } + } + else if ( ivert == 1 ) { + if ( face_num < FACE_MAX ) { + face[ivert][face_num] = jval + cor3_num_old; + } + } + else if ( ivert == 2 ) { + if ( face_num < FACE_MAX ) { + face[ivert][face_num] = jval + cor3_num_old; + } + face_num = face_num + 1; + } + else { + + if ( face_num < FACE_MAX ) { + face_order[face_num] = 3; + if ( ( ivert % 2 ) == 0 ) { + face[0][face_num] = ix; + face[1][face_num] = iy; + face[2][face_num] = iz; + } + else { + face[0][face_num] = iz; + face[1][face_num] = iy; + face[2][face_num] = ix; + } + } + face_num = face_num + 1; + } + ivert = ivert + 1; +/* + Very very tentative guess as to how indices into the normal + vector array are set up... +*/ + if ( face_num < FACE_MAX && ivert > 2 ) { + for ( i = 0; i < 3; i++ ) { + face_normal[i][face_num] = normal_temp[i][ix]; + } + } + } + } + } + } +/* + INDEXEDFACESET +*/ + else if ( leqi ( level_name[level], "INDEXEDFACESET" ) == TRUE ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( leqi ( word, "COORDINDEX" ) == TRUE ) { + ivert = 0; + } + else if ( leqi ( word, "MATERIALINDEX" ) == TRUE ) { + } + else if ( leqi ( word, "NORMALINDEX" ) == TRUE ) { + } + else if ( leqi ( word, "TEXTURECOORDINDEX" ) == TRUE ) { + if ( texture_num <= 0 ) { + texture_num = 1; + strcpy ( texture_name[0], "Texture_0000" ); + } + } + else { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } +/* + INDEXEDLINESET +*/ + else if ( leqi ( level_name[level], "INDEXEDLINESET" ) == TRUE ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( leqi ( word, "COORDINDEX" ) == TRUE ) { + } + else if ( leqi ( word, "MATERIALINDEX" ) == TRUE ) { + } + else { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } +/* + INDEXEDNURBSSURFACE +*/ + else if ( leqi ( level_name[level], "INDEXEDNURBSSURFACE" ) == TRUE ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( leqi ( word, "NUMUCONTROLPOINTS") == TRUE ) { + + count = sscanf ( word, "%d%n", &jval, &width ); + + if ( count > 0 ) { + nu = jval; + if ( debug ) { + printf ( "NU = %d\n", nu ); + } + } + else { + nu = 0; + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } + else if ( leqi ( word, "NUMVCONTROLPOINTS" ) == TRUE ) { + + count = sscanf ( word, "%d%n", &jval, &width ); + + if ( count > 0 ) { + nv = jval; + if ( debug ) { + printf ( "NV = %d\n", nv ); + } + } + else { + nv = 0; + bad_num = bad_num + 1; + } + } + else if ( leqi ( word, "COORDINDEX" ) == TRUE ) { + } + else if ( leqi ( word, "UKNOTVECTOR" ) == TRUE ) { + } + else if ( leqi ( word, "VKNOTVECTOR" ) == TRUE ) { + } + else { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } +/* + INDEXEDTRIANGLESTRIPSET +*/ + else if ( leqi ( level_name[level], "INDEXEDTRIANGLESTRIPSET" ) == TRUE ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( leqi ( word, "VERTEXPROPERTY" ) == TRUE ) { + count = sscanf ( next, "%s%n", word, &width ); + next = next + width; + } + else if ( leqi ( word, "COORDINDEX" ) == TRUE ) { + ivert = 0; + } + else if ( leqi ( word, "NORMALINDEX" ) == TRUE ) { + count = sscanf ( next, "%s%n", word, &width ); + next = next + width; + } + else { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } +/* + INFO +*/ + else if ( leqi ( level_name[level], "INFO" ) == TRUE ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( leqi ( word, "STRING" ) == TRUE ) { + } + else if ( strcmp ( word, "\"" ) == 0 ) { + } + else { + } + } +/* + LIGHTMODEL + Read, but ignore. +*/ + else if ( leqi ( level_name[level], "LIGHTMODEL" ) == TRUE ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( leqi ( word, "model" ) == TRUE ) { + } + else { + } + } +/* + MATERIAL + Read, but ignore. +*/ + else if ( leqi ( level_name[level],"MATERIAL" ) == TRUE ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( leqi ( word, "AMBIENTCOLOR" ) == TRUE ) { + } + else if ( leqi ( word, "EMISSIVECOLOR" ) == TRUE ) { + } + else if ( leqi ( word, "DIFFUSECOLOR" ) == TRUE ) { + } + else if ( leqi ( word, "SHININESS" ) == TRUE ) { + } + else if ( leqi ( word, "SPECULARCOLOR" ) == TRUE ) { + } + else if ( leqi ( word, "TRANSPARENCY" ) == TRUE ) { + } + else { + } + } +/* + MATERIALBINDING + Read, but ignore +*/ + else if ( leqi ( level_name[level], "MATERIALBINDING" ) == TRUE ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( leqi ( word, "VALUE" ) == TRUE ) { + count = sscanf ( next, "%s%n", material_binding, &width ); + next = next + width; + } + else { + count = sscanf ( next, "%f%n", &rval, &width ); + next = next + width; + + if ( count > 0 ) { + } + else { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } + } +/* + MATERIALINDEX +*/ + else if ( leqi ( level_name[level], "MATERIALINDEX" ) == TRUE ) { + + if ( strcmp ( word, "[" ) == 0 ) { + ivert = 0; + } + else if ( strcmp ( word, "]" ) == 0 ) { + level = nlbrack - nrbrack; + } +/* + (indexedfaceset) MATERIALINDEX +*/ + else if ( leqi ( level_name[level-1], "INDEXEDFACESET" ) == TRUE ) { + + count = sscanf ( word, "%d%n", &jval, &width ); + + if ( count > 0 ) { + + if ( jval == -1 ) { + ivert = 0; + face_num2 = face_num2 + 1; + } + else { + + if ( face_num2 < FACE_MAX ) { + if ( jval != -1 ) { + jval = jval + cor3_num_old; + } + vertex_material[ivert][face_num2] = jval; + ivert = ivert + 1; + } + } + } + else { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } +/* + (indexedlineset) MATERIALINDEX +*/ + else if ( leqi ( level_name[level-1], "INDEXEDLINESET" ) == TRUE ) { + + count = sscanf ( word, "%d%n", &jval, &width ); + + if ( count > 0 ) { + + if ( line_num2 < LINES_MAX ) { + if ( jval != -1 ) { + jval = jval + cor3_num_old; + } + line_material[line_num2] = jval; + line_num2 = line_num2 + 1; + } + } + else { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } + else { + count = sscanf ( word, "%d%n", &jval, &width ); + + if ( count > 0 ) { + } + else { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } + } +/* + MATRIXTRANSFORM. +*/ + else if ( leqi ( level_name[level], "MATRIXTRANSFORM" ) == TRUE ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( leqi ( word, "MATRIX" ) == TRUE ) { + icol = -1; + irow = 0; + } + else { + + count = sscanf ( word, "%f%n", &rval, &width ); + + if ( count > 0 ) { + + icol = icol + 1; + if ( icol > 3 ) { + icol = 0; + irow = irow + 1; + if ( irow > 3 ) { + irow = 0; + } + } + + transform_matrix[irow][icol] = rval; + } + + } + } +/* + NORMAL + The field "VECTOR" may be followed by three numbers, + (handled here), or by a square bracket, and sets of three numbers. +*/ + else if ( leqi ( level_name[level], "NORMAL" ) == TRUE ) { +/* + (vertexproperty) NORMAL +*/ + if ( leqi ( level_name[level-1], "VERTEXPROPERTY" ) == TRUE ) { + + if ( strcmp ( word, "[" ) == 0 ) { + ixyz = 0; + } + else if ( strcmp ( word, "]" ) == 0 ) { + level = nlbrack - nrbrack; + } + else { + + count = sscanf ( word, "%f%n", &rval, &width ); + + if ( count > 0 ) { + + if ( inormface < FACE_MAX ) { + face_normal[ixyz][inormface] = rval; + } + + ixyz = ixyz + 1; + if ( ixyz > 2 ) { + ixyz = 0; + inormface = inormface + 1; + } + } + } + } +/* + (anythingelse) NORMAL +*/ + else { + + if ( strcmp ( word, "{" ) == 0 ) { + ixyz = 0; + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( leqi ( word, "VECTOR" ) == TRUE ) { + } + else { + + count = sscanf ( word, "%f%n", &rval, &width ); + + if ( count > 0 ) { + +/* COMMENTED OUT + + if ( nfnorm < FACE_MAX ) { + normal[ixyz][nfnorm] = rval; + } + +*/ + ixyz = ixyz + 1; + if ( ixyz > 2 ) { + ixyz = 0; + } + } + else { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } + } + } +/* + NORMALBINDING + Read, but ignore +*/ + else if ( leqi ( level_name[level], "NORMALBINDING" ) == TRUE ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( leqi ( word, "VALUE" ) == TRUE ) { + count = sscanf ( next, "%s%n", normal_binding, &width ); + next = next + width; + } + else { + count = sscanf ( word, "%f%n", &rval, &width ); + + if ( count > 0 ) { + } + else { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } + } +/* + NORMALINDEX +*/ + else if ( leqi ( level_name[level], "NORMALINDEX" ) == TRUE ) { +/* + (indexedtrianglestripset) NORMALINDEX +*/ + if ( leqi ( level_name[level-1], "INDEXEDTRIANGLESTRIPSET" ) == TRUE ) { + count = sscanf ( word, "%d%n", &jval, &width ); + + if ( count > 0 ) { + } + else if ( strcmp ( word, "[" ) == 0 ) { + } + else if ( strcmp ( word, "]" ) == 0 ) { + } + } +/* + (anythingelse) NORMALINDEX +*/ + else { + + if ( strcmp ( word, "[" ) == 0 ) { + ivert = 0; + } + else if ( strcmp ( word, "]" ) == 0 ) { + level = nlbrack - nrbrack; + } + else { + + count = sscanf ( word, "%d%n", &jval, &width ); + + if ( count > 0 ) { + if ( jval == -1 ) { + ivert = 0; + iface_num = iface_num + 1; + } + else { + if ( iface_num < FACE_MAX ) { + for ( i = 0; i < 3; i++ ){ + vertex_normal[i][ivert][iface_num] = normal_temp[i][jval]; + } + ivert = ivert + 1; + } + } + } + else { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } + } + } +/* + (coordinate3) POINT +*/ + else if ( leqi ( level_name[level], "POINT" ) == TRUE ) { + + if ( leqi ( level_name[level-1], "COORDINATE3" ) == TRUE ) { + + if ( strcmp ( word, "[" ) == 0 ) { + ixyz = 0; + cor3_num_old = cor3_num; + } + else if ( strcmp ( word, "]" ) == 0 ) { + level = nlbrack - nrbrack; + } + else { + + count = sscanf ( word, "%f%n", &rval, &width ); + + if ( count > 0 ) { + + if ( cor3_num < COR3_MAX ) { + xvec[ixyz] = rval; + } + + ixyz = ixyz + 1; + + if ( ixyz == 3 ) { + + ixyz = 0; + + tmat_mxp ( transform_matrix, xvec, xvec ); + + cor3[0][cor3_num] = xvec[0]; + cor3[1][cor3_num] = xvec[1]; + cor3[2][cor3_num] = xvec[2]; + + cor3_num = cor3_num + 1; + + continue; + } + } + else { + bad_num = bad_num + 1; + break; + } + } + } +/* + (texturecoodinate2) POINT +*/ + else if ( leqi ( level_name[level-1], "TEXTURECOORDINATE2" ) == TRUE ) { + + if ( strcmp ( word, "[" ) == 0 ) { + iuv = 0; + text_numure_temp = 0; + } + else if ( strcmp ( word, "]" ) == 0 ) { + level = nlbrack - nrbrack; + } + else { + + count = sscanf ( word, "%f%n", &rval, &width ); + + if ( count > 0 ) { + + texture_temp[iuv][text_numure_temp] = rval; + + iuv = iuv + 1; + if ( iuv == 2 ) { + iuv = 0; + text_numure_temp = text_numure_temp + 1; + } + } + else { + printf ( "TextureCoordinate2 { Point [: Bad data\n" ); + bad_num = bad_num + 1; + break; + } + } + } + } +/* + RGB +*/ + else if ( leqi ( level_name[level],"RGB" ) == TRUE ) { +/* + (basecolor) RGB +*/ + if ( leqi ( level_name[level-1], "BASECOLOR" ) == TRUE ) { + + if ( strcmp ( word, "[" ) == 0 ) { + icolor = 0; + } + else if ( strcmp ( word, "]" ) == 0 ) { + level = nlbrack - nrbrack; + } + else { + + count = sscanf ( word, "%f%n", &rval, &width ); + + if ( count > 0 ) { + + rgbcolor[icolor][color_num] = rval; + icolor = icolor + 1; + + if ( icolor == 3 ) { + icolor = 0; + color_num = color_num + 1; + } + } + else { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } + } +/* + (anythingelse RGB) +*/ + else { + + printf ( "HALSBAND DES TODES!\n" ); + + if ( strcmp ( word, "[" ) == 0 ) { + icolor = 0; + ivert = 0; + } + else if ( strcmp ( word, "]" ) == 0 ) { + level = nlbrack - nrbrack; + } + else { + + count = sscanf ( word, "%f%n", &rval, &width ); + + if ( count > 0 ) { + + if ( icface < FACE_MAX ) { + + vertex_rgb[icolor][ivert][icface] = rval; + + icolor = icolor + 1; + if ( icolor == 3 ) { + icolor = 0; + color_num = color_num + 1; + ivert = ivert + 1; + if ( ivert == face_order[icface] ) { + ivert = 0; + icface = icface + 1; + } + } + } + } + else { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } + } + + } +/* + SEPARATOR +*/ + else if ( leqi ( level_name[level], "SEPARATOR" ) == TRUE ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else { + } + } +/* + SHAPEHINTS + Read, but ignore. +*/ + else if ( leqi ( level_name[level], "SHAPEHINTS" ) == TRUE ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( leqi ( word, "CREASEANGLE" ) == TRUE ) { + + count = sscanf ( next, "%f%n", &rval, &width ); + next = next + width; + + if ( count <= 0 ) { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } + else if ( leqi ( word, "FACETYPE" ) == TRUE ) { + count = sscanf ( next, "%s%n", word, &width ); + next = next + width; + } + else if ( leqi ( word, "SHAPETYPE" ) == TRUE ) { + count = sscanf ( next, "%s%n", word, &width ); + next = next + width; + } + else if ( leqi ( word, "VERTEXORDERING" ) == TRUE ) { + count = sscanf ( next, "%s%n", word, &width ); + next = next + width; + } + else { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } +/* + TEXTURE2 +*/ + else if ( leqi ( level_name[level], "TEXTURE2" ) == TRUE ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + texture_num = texture_num + 1; + } + else if ( leqi ( word, "BLENDCOLOR" ) == TRUE ) { + } +/* + NEED TO REMOVE QUOTES SURROUNDING TEXTURE NAME. +*/ + else if ( leqi ( word, "FILENAME" ) == TRUE ) { + + count = sscanf ( next, "%s%n", word, &width ); + next = next + width; + + strcpy ( texture_name[texture_num], word ); + + i = 0; + j = 0; + do { + c = texture_name[texture_num][i]; + i = i + 1; + if ( c != '"' ) { + texture_name[texture_num][j] = c; + j = j + 1; + } + } while ( c != '\0' ); + + } + else if ( leqi ( word, "IMAGE" ) == TRUE ) { + } + else if ( leqi ( word, "MODEL" ) == TRUE ) { + count = sscanf ( next, "%s%n", word, &width ); + next = next + width; + } + else if ( leqi ( word, "WRAPS" ) == TRUE ) { + count = sscanf ( next, "%s%n", word, &width ); + next = next + width; + } + else if ( leqi ( word, "WRAPT" ) == TRUE ) { + count = sscanf ( next, "%s%n", word, &width ); + next = next + width; + } + else { + } + } +/* + TEXTURECOORDINATE2 +*/ + else if ( leqi ( level_name[level], "TEXTURECOORDINATE2" ) == TRUE ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( leqi ( word, "POINT" ) == TRUE ) { + } + else { + bad_num = bad_num + 1; + printf ( "TEXTURECOORDINATE2: Bad data %s\n", word ); + } + } +/* + TEXTURECOORDINATEBINDING +*/ + else if ( leqi ( level_name[level], "TEXTURECOORDINATEBINDING" ) == TRUE ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( leqi ( word, "VALUE" ) == TRUE ) { + count = sscanf ( next, "%s%n", texture_binding, &width ); + next = next + width; + } + else { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } +/* + TEXTURECOORDINDEX +*/ + else if ( leqi ( level_name[level], "TEXTURECOORDINDEX" ) == TRUE ) { + + if ( strcmp ( word, "[" ) == 0 ) { + ivert = 0; + iface_num = 0; + } + else if ( strcmp ( word, "]" ) == 0 ) { + level = nlbrack - nrbrack; + } + else { + + count = sscanf ( word, "%d%n", &jval, &width ); + + if ( count > 0 ) { + + if ( jval == - 1 ) { + ivert = 0; + } + else { + + if ( iface_num < FACE_MAX ) { + vertex_tex_uv[0][ivert][iface_num] = texture_temp[0][jval]; + vertex_tex_uv[1][ivert][iface_num] = texture_temp[1][jval]; + } + + ivert = ivert + 1; + + if ( ivert == face_order[iface_num] ) { + ivert = 0; + iface_num = iface_num + 1; + } + } + + } + else { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + + } + } +/* + UKNOTVECTOR +*/ + else if ( leqi ( level_name[level], "UKNOTVECTOR" ) == TRUE ) { + + if ( strcmp ( word, "[" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "]" ) == 0 ) { + level = nlbrack - nrbrack; + continue; + } + else { + count = sscanf ( word, "%d%n", &jval, &width ); + } + } +/* + VECTOR +*/ + else if ( leqi ( level_name[level], "VECTOR" ) == TRUE ) { + if ( strcmp ( word, "[" ) == 0 ) { + } + else if ( strcmp ( word, "]" ) == 0 ) { + level = nlbrack - nrbrack; + } +/* + (normal) VECTOR +*/ + else if ( leqi ( level_name[level-1], "NORMAL" ) == TRUE ) { + + count = sscanf ( word, "%f%n", &rval, &width ); + + if ( count > 0 ) { + + if ( normal_num_temp < ORDER_MAX * FACE_MAX ) { + normal_temp[ixyz][normal_num_temp] = rval; + ixyz = ixyz + 1; + if ( ixyz == 3 ) { + ixyz = 0; + normal_num_temp = normal_num_temp + 1; + } + } + } + else { + bad_num = bad_num + 1; + printf ( "NORMAL VECTOR: bad data %s\n", word ); + } + } + } +/* + (vertexproperty) VERTEX +*/ + else if ( leqi ( level_name[level], "VERTEX" ) == TRUE ) { + + if ( leqi ( level_name[level-1], "VERTEXPROPERTY" ) == TRUE ) { + + if ( strcmp ( word, "[" ) == 0 ) { + ixyz = 0; + cor3_num_old = cor3_num; + } + else if ( strcmp ( word, "]" ) == 0 ) { + level = nlbrack - nrbrack; + } + else { + count = sscanf ( word, "%f%n", &rval, &width ); + + if ( count > 0 ) { + + if ( cor3_num < COR3_MAX ) { + cor3[ixyz][cor3_num] = rval; + } + ixyz = ixyz + 1; + if ( ixyz == 3 ) { + ixyz = 0; + cor3_num = cor3_num + 1; + } + + } + else { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } + } + } +/* + (indexedtrianglestripset) VERTEXPROPERTY +*/ + else if ( leqi ( level_name[level], "VERTEXPROPERTY" ) == TRUE ) { + + if ( strcmp ( word, "{" ) == 0 ) { + } + else if ( strcmp ( word, "}" ) == 0 ) { + level = nlbrack - nrbrack; + } + else if ( leqi ( word, "VERTEX" ) == TRUE ) { + } + else if ( leqi ( word, "NORMAL" ) == TRUE ) { + ixyz = 0; + } + else if ( leqi ( word, "MATERIALBINDING" ) == TRUE ) { + count = sscanf ( next, "%s%n", word, &width ); + next = next + width; + } + else if ( leqi ( word, "NORMALBINDING" ) == TRUE ) { + count = sscanf ( next, "%s%n", word, &width ); + next = next + width; + } + else { + bad_num = bad_num + 1; + printf ( "Bad data %s\n", word ); + } + } +/* + VKNOTVECTOR +*/ + else if ( leqi ( level_name[level], "VKNOTVECTOR" ) == TRUE ) { + + if ( strcmp ( word, "[" ) == 0 ) { + continue; + } + else if ( strcmp ( word, "]" ) == 0 ) { + level = nlbrack - nrbrack; + continue; + } + else { + count = sscanf ( word, "%d%n", &jval, &width ); + } + } +/* + Any other word: +*/ + else { + } + } + } +/* + Reset the transformation matrix to the identity, + because, presumably, we've applied it by now. +*/ + tmat_init ( transform_matrix ); + + return SUCCESS; +} +/******************************************************************************/ + +int iv_write ( FILE *fileout ) + +/******************************************************************************/ + +/* + Purpose: + + IV_WRITE writes graphics information to an Inventor file. + + Modified: + + 29 June 1999 + + Author: + + John Burkardt +*/ +{ + int icor3; + int iface; + int itemp; + int ivert; + int j; + int length; + int text_num; + + text_num = 0; + + fprintf ( fileout, "#Inventor V2.0 ascii\n" ); + fprintf ( fileout, "\n" ); + fprintf ( fileout, "Separator {\n" ); + fprintf ( fileout, " Info {\n" ); + fprintf ( fileout, " string \"%s generated by IVCON.\"\n", fileout_name ); + fprintf ( fileout, " string \"Original data in file %s.\"\n", filein_name ); + fprintf ( fileout, " }\n" ); + fprintf ( fileout, " Separator {\n" ); + text_num = text_num + 8; +/* + LightModel: + + BASE_COLOR ignores light sources, and uses only diffuse color + and transparency. Even without normal vector information, + the object will show up. However, you won't get shadow + and lighting effects. + + PHONG uses the Phong lighting model, accounting for light sources + and surface orientation. This is the default. I believe + you need accurate normal vector information in order for this + option to produce nice pictures. + + DEPTH ignores light sources, and calculates lighting based on + the location of the object within the near and far planes + of the current camera's view volume. +*/ + fprintf ( fileout, " LightModel {\n" ); + fprintf ( fileout, " model PHONG\n" ); + fprintf ( fileout, " }\n" ); + text_num = text_num + 3; +/* + Transformation matrix. +*/ + fprintf ( fileout, " MatrixTransform { matrix\n" ); + fprintf ( fileout, " %f %f %f %f\n", transform_matrix[0][0], + transform_matrix[0][1], transform_matrix[0][2], transform_matrix[0][3] ); + fprintf ( fileout, " %f %f %f %f\n", transform_matrix[1][0], + transform_matrix[1][1], transform_matrix[1][2], transform_matrix[1][3] ); + fprintf ( fileout, " %f %f %f %f\n", transform_matrix[2][0], + transform_matrix[2][1], transform_matrix[2][2], transform_matrix[2][3] ); + fprintf ( fileout, " %f %f %f %f\n", transform_matrix[3][0], + transform_matrix[3][1], transform_matrix[3][2], transform_matrix[3][3] ); + fprintf ( fileout, " }\n" ); + text_num = text_num + 6; +/* + Material. +*/ + fprintf ( fileout, " Material {\n" ); + fprintf ( fileout, " ambientColor 0.2 0.2 0.2\n" ); + fprintf ( fileout, " diffuseColor 0.8 0.8 0.8\n" ); + fprintf ( fileout, " emissiveColor 0.0 0.0 0.0\n" ); + fprintf ( fileout, " specularColor 0.0 0.0 0.0\n" ); + fprintf ( fileout, " shininess 0.2\n" ); + fprintf ( fileout, " transparency 0.0\n" ); + fprintf ( fileout, " }\n" ); + text_num = text_num + 8; +/* + MaterialBinding +*/ + fprintf ( fileout, " MaterialBinding {\n" ); + fprintf ( fileout, " value PER_VERTEX_INDEXED\n" ); + fprintf ( fileout, " }\n" ); + text_num = text_num + 3; +/* + NormalBinding + + PER_VERTEX promises that we will write a list of normal vectors + in a particular order, namely, the normal vectors for the vertices + of the first face, then the second face, and so on. + + PER_VERTEX_INDEXED promises that we will write a list of normal vectors, + and then, as part of the IndexedFaceSet, we will give a list of + indices referencing this normal vector list. +*/ + fprintf ( fileout, " NormalBinding {\n" ); + fprintf ( fileout, " value PER_VERTEX_INDEXED\n" ); + fprintf ( fileout, " }\n" ); + text_num = text_num + 3; +/* + Texture2. + + FLAW: We can only handle on texture right now. +*/ + if ( texture_num > 0 ) { + fprintf ( fileout, " Texture2 {\n" ); + fprintf ( fileout, " filename \"%s\"\n", texture_name[0] ); + fprintf ( fileout, " wrapS REPEAT\n" ); + fprintf ( fileout, " wrapT REPEAT\n" ); + fprintf ( fileout, " model MODULATE\n" ); + fprintf ( fileout, " blendColor 0.0 0.0 0.0\n" ); + fprintf ( fileout, " }\n" ); + text_num = text_num + 7; + } +/* + TextureCoordinateBinding +*/ + fprintf ( fileout, " TextureCoordinateBinding {\n" ); + fprintf ( fileout, " value PER_VERTEX_INDEXED\n" ); + fprintf ( fileout, " }\n" ); + text_num = text_num + 3; +/* + ShapeHints +*/ + fprintf ( fileout, " ShapeHints {\n" ); + fprintf ( fileout, " vertexOrdering COUNTERCLOCKWISE\n" ); + fprintf ( fileout, " shapeType UNKNOWN_SHAPE_TYPE\n" ); + fprintf ( fileout, " faceType CONVEX\n" ); + fprintf ( fileout, " creaseAngle 6.28319\n" ); + fprintf ( fileout, " }\n" ); + text_num = text_num + 6; +/* + Point coordinates. +*/ + fprintf ( fileout, " Coordinate3 {\n" ); + fprintf ( fileout, " point [\n" ); + text_num = text_num + 2; + + for ( j = 0; j < cor3_num; j++ ) { + fprintf ( fileout, " %f %f %f,\n", cor3[0][j], cor3[1][j], cor3[2][j] ); + text_num = text_num + 1; + } + fprintf ( fileout, " ]\n" ); + fprintf ( fileout, " }\n" ); + text_num = text_num + 2; +/* + Texture coordinates. +*/ + fprintf ( fileout, " TextureCoordinate2 {\n" ); + fprintf ( fileout, " point [\n" ); + text_num = text_num + 2; + + for ( iface = 0; iface < face_num; iface++ ) { + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + fprintf ( fileout, " %f %f,\n", vertex_tex_uv[0][ivert][iface], + vertex_tex_uv[1][ivert][iface] ); + text_num = text_num + 1; + } + } + fprintf ( fileout, " ]\n" ); + fprintf ( fileout, " }\n" ); + text_num = text_num + 2; +/* + BaseColor. +*/ + if ( color_num > 0 ) { + + fprintf ( fileout, " BaseColor {\n" ); + fprintf ( fileout, " rgb [\n" ); + text_num = text_num + 2; + + for ( j = 0; j < color_num; j++ ) { + fprintf ( fileout, " %f %f %f,\n", rgbcolor[0][j], rgbcolor[1][j], + rgbcolor[2][j] ); + text_num = text_num + 1; + } + + fprintf ( fileout, " ]\n" ); + fprintf ( fileout, " }\n" ); + text_num = text_num + 2; + } +/* + Normal vectors. + Use the normal vectors associated with nodes. +*/ + if ( face_num > 0 ) { + + fprintf ( fileout, " Normal { \n" ); + fprintf ( fileout, " vector [\n" ); + text_num = text_num + 2; + + for ( icor3 = 0; icor3 < cor3_num; icor3++ ) { + fprintf ( fileout, " %f %f %f,\n", + cor3_normal[0][icor3], + cor3_normal[1][icor3], + cor3_normal[2][icor3] ); + text_num = text_num + 1; + } + + fprintf ( fileout, " ]\n" ); + fprintf ( fileout, " }\n" ); + text_num = text_num + 2; + } +/* + IndexedLineSet +*/ + if ( line_num > 0 ) { + + fprintf ( fileout, " IndexedLineSet {\n" ); +/* + IndexedLineSet coordIndex +*/ + fprintf ( fileout, " coordIndex [\n" ); + text_num = text_num + 2; + + length = 0; + + for ( j = 0; j < line_num; j++ ) { + + if ( length == 0 ) { + fprintf ( fileout, " " ); + } + + fprintf ( fileout, " %d,", line_dex[j] ); + length = length + 1; + + if ( line_dex[j] == -1 || length >= 10 || j == line_num-1 ) { + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + length = 0; + } + } + + fprintf ( fileout, " ]\n" ); + text_num = text_num + 1; +/* + IndexedLineSet materialIndex. +*/ + fprintf ( fileout, " materialIndex [\n" ); + text_num = text_num + 1; + + length = 0; + + for ( j = 0; j < line_num; j++ ) { + + if ( length == 0 ) { + fprintf ( fileout, " " ); + } + + fprintf ( fileout, " %d,", line_material[j] ); + length = length + 1; + + if ( line_material[j] == -1 || length >= 10 || j == line_num-1 ) { + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + length = 0; + } + } + + fprintf ( fileout, " ]\n" ); + fprintf ( fileout, " }\n" ); + text_num = text_num + 2; + } +/* + IndexedFaceSet. +*/ + if ( face_num > 0 ) { + + fprintf ( fileout, " IndexedFaceSet {\n" ); + fprintf ( fileout, " coordIndex [\n" ); + text_num = text_num + 2; + + for ( iface = 0; iface < face_num; iface++ ) { + + fprintf ( fileout, " " ); + + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + fprintf ( fileout, " %d,", face[ivert][iface] ); + } + fprintf ( fileout, " -1,\n" ); + text_num = text_num + 1; + } + + fprintf ( fileout, " ]\n" ); + text_num = text_num + 1; +/* + IndexedFaceSet normalIndex +*/ + fprintf ( fileout, " normalIndex [\n" ); + text_num = text_num + 1; + + for ( iface = 0; iface < face_num; iface++ ) { + + fprintf ( fileout, " " ); + + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + fprintf ( fileout, " %d,", face[ivert][iface] ); + } + fprintf ( fileout, " -1,\n" ); + text_num = text_num + 1; + } + fprintf ( fileout, " ]\n" ); + text_num = text_num + 1; +/* + IndexedFaceSet materialIndex +*/ + fprintf ( fileout, " materialIndex [\n" ); + text_num = text_num + 1; + + for ( iface = 0; iface < face_num; iface++ ) { + + fprintf ( fileout, " " ); + + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + fprintf ( fileout, " %d,", vertex_material[ivert][iface] ); + } + fprintf ( fileout, " -1,\n" ); + text_num = text_num + 1; + } + + fprintf ( fileout, " ]\n" ); + text_num = text_num + 1; +/* + IndexedFaceSet textureCoordIndex +*/ + fprintf ( fileout, " textureCoordIndex [\n" ); + text_num = text_num + 1; + + itemp = 0; + + for ( iface = 0; iface < face_num; iface++ ) { + + fprintf ( fileout, " " ); + + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + fprintf ( fileout, " %d,", itemp ); + itemp = itemp + 1; + } + fprintf ( fileout, " -1,\n" ); + text_num = text_num + 1; + } + + fprintf ( fileout, " ]\n" ); + + fprintf ( fileout, " }\n" ); + text_num = text_num + 2; + } +/* + Close up the Separator nodes. +*/ + fprintf ( fileout, " }\n" ); + fprintf ( fileout, "}\n" ); + text_num = text_num + 2; +/* + Report. +*/ + printf ( "\n" ); + printf ( "IV_WRITE - Wrote %d text lines;\n", text_num ); + + return SUCCESS; +} +/******************************************************************************/ + +int ivec_max ( int n, int *a ) + +/******************************************************************************/ + +/* + Purpose: + + IVEC_MAX returns the maximum element in an integer array. + + Modified: + + 09 October 1998 + + Author: + + John Burkardt +*/ +{ + int i; + int *ia; + int imax; + + if ( n <= 0 ) { + imax = 0; + } + else { + ia = a; + imax = *ia; + for ( i = 1; i < n; i++ ) { + ia = ia + 1; + if ( imax < *ia ) { + imax = *ia; + } + } + } + return imax; +} +/******************************************************************************/ + +int leqi ( char* string1, char* string2 ) + +/******************************************************************************/ + +/* + Purpose: + + LEQI compares two strings for equality, disregarding case. + + Modified: + + 15 September 1998 + + Author: + + John Burkardt +*/ +{ + int i; + int nchar; + int nchar1; + int nchar2; + + nchar1 = strlen ( string1 ); + nchar2 = strlen ( string2 ); + + if ( nchar1 < nchar2 ) { + nchar = nchar1; + } + else { + nchar = nchar2; + } +/* + The strings are not equal if they differ over their common length. +*/ + for ( i = 0; i < nchar; i++ ) { + + if ( toupper ( string1[i] ) != toupper ( string2[i] ) ) { + return FALSE; + } + } +/* + The strings are not equal if the longer one includes nonblanks + in the tail. +*/ + if ( nchar1 > nchar ) { + for ( i = nchar; i < nchar1; i++ ) { + if ( string1[i] != ' ' ) { + return FALSE; + } + } + } + else if ( nchar2 > nchar ) { + for ( i = nchar; i < nchar2; i++ ) { + if ( string2[i] != ' ' ) { + return FALSE; + } + } + } + return TRUE; +} +/******************************************************************************/ + +long int long_int_read ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + LONG_INT_READ reads a long int from a binary file. + + Modified: + + 24 May 1999 + + Author: + + John Burkardt +*/ +{ + union { + long int yint; + char ychar[4]; + } y; + + if ( byte_swap == TRUE ) { + y.ychar[3] = fgetc ( filein ); + y.ychar[2] = fgetc ( filein ); + y.ychar[1] = fgetc ( filein ); + y.ychar[0] = fgetc ( filein ); + } + else { + y.ychar[0] = fgetc ( filein ); + y.ychar[1] = fgetc ( filein ); + y.ychar[2] = fgetc ( filein ); + y.ychar[3] = fgetc ( filein ); + } + + return y.yint; +} +/******************************************************************************/ + +int long_int_write ( FILE *fileout, long int int_val ) + +/******************************************************************************/ + +/* + Purpose: + + LONG_INT_WRITE writes a long int to a binary file. + + Modified: + + 14 October 1998 + + Author: + + John Burkardt +*/ +{ + union { + long int yint; + char ychar[4]; + } y; + + y.yint = int_val; + + if ( byte_swap == TRUE ) { + fputc ( y.ychar[3], fileout ); + fputc ( y.ychar[2], fileout ); + fputc ( y.ychar[1], fileout ); + fputc ( y.ychar[0], fileout ); + } + else { + fputc ( y.ychar[0], fileout ); + fputc ( y.ychar[1], fileout ); + fputc ( y.ychar[2], fileout ); + fputc ( y.ychar[3], fileout ); + } + + return 4; +} +/******************************************************************************/ + +void news ( void ) + +/******************************************************************************/ + +/* + Purpose: + + NEWS reports the program change history. + + Modified: + + 26 September 1999 + + Author: + + John Burkardt +*/ +{ + printf ( "\n" ); + printf ( "Recent changes:\n" ); + printf ( "\n" ); + printf ( " 04 July 2000\n" ); + printf ( " Added preliminary XGL_WRITE.\n" ); + printf ( " 26 September 1999\n" ); + printf ( " After ASE_READ, call NODE_TO_VERTEX_MAT and VERTEX_TO_FACE_MATERIAL.\n" ); + printf ( " 27 July 1999\n" ); + printf ( " Corrected TMAT_ROT_VECTOR.\n" ); + printf ( " 17 July 1999\n" ); + printf ( " Added null edge and face deletion.\n" ); + printf ( " Corrected a string problem in SMF_READ.\n" ); + printf ( " 03 July 1999\n" ); + printf ( " Fixed a problem with BINDING variables in SMF_READ.\n" ); + printf ( " 02 July 1999\n" ); + printf ( " Added limited texture support in 3DS/IV.\n" ); + printf ( " 26 June 1999\n" ); + printf ( " BYU_READ added.\n" ); + printf ( " 25 June 1999\n" ); + printf ( " BYU_WRITE added.\n" ); + printf ( " 22 June 1999\n" ); + printf ( " TRIB_READ added.\n" ); + printf ( " 16 June 1999\n" ); + printf ( " TRIB_WRITE Greg Hood binary triangle output routine added.\n" ); + printf ( " 10 June 1999\n" ); + printf ( " TRIA_WRITE Greg Hood ASCII triangle output routine added.\n" ); + printf ( " 09 June 1999\n" ); + printf ( " TEC_WRITE TECPLOT output routine added.\n" ); + printf ( " IV_READ and IV_WRITE use TRANSFORM_MATRIX now.\n" ); + printf ( " 26 May 1999\n" ); + printf ( " LINE_PRUNE option added for VLA_WRITE.\n" ); + printf ( " 24 May 1999\n" ); + printf ( " Added << command to append new graphics data to old.\n" ); + printf ( " Stuck in first draft STLB_READ/STLB_WRITE routines.\n" ); + printf ( " STLA_WRITE and STLB_WRITE automatically decompose \n" ); + printf ( " non-triangular faces before writing.\n" ); + printf ( " 23 May 1999\n" ); + printf ( " Stuck in first draft WRL_WRITE routine.\n" ); + printf ( " 22 May 1999\n" ); + printf ( " Faces converted to lines before calling VLA_WRITE.\n" ); + printf ( " Added UCD_WRITE.\n" ); + printf ( " Added MATERIAL/PATCH/TAGGEDPOINTS fields in HRC_READ.\n" ); + printf ( " 17 May 1999\n" ); + printf ( " Updated SMF_WRITE, SMF_READ to match code in IVREAD.\n" ); + printf ( " Added transformation matrix routines.\n" ); + printf ( " 16 May 1999\n" ); + printf ( " Zik Saleeba improved DXF support to handle polygons.\n" ); + printf ( " 15 April 1999\n" ); + printf ( " Zik Saleeba added Golgotha GMOD file format support.\n" ); + printf ( " 03 December 1998\n" ); + printf ( " Set up simple hooks in TDS_READ_MATERIAL_SECTION.\n" ); + printf ( " 02 December 1998\n" ); + printf ( " Set up simple hooks for texture map names.\n" ); + printf ( " 19 November 1998\n" ); + printf ( " IV_WRITE uses PER_VERTEX normal binding.\n" ); + printf ( " 18 November 1998\n" ); + printf ( " Added node normals.\n" ); + printf ( " Finally added the -RN option.\n" ); + printf ( " 17 November 1998\n" ); + printf ( " Added face node ordering reversal option.\n" ); + printf ( " 20 October 1998\n" ); + printf ( " Added DATA_REPORT.\n" ); + printf ( " 19 October 1998\n" ); + printf ( " SMF_READ and SMF_WRITE added.\n" ); + printf ( " 16 October 1998\n" ); + printf ( " Fixing a bug in IV_READ that chokes on ]} and other\n" ); + printf ( " cases where brackets aren't properly spaced.\n" ); + printf ( " 11 October 1998\n" ); + printf ( " Added face subset selection option S.\n" ); + printf ( " 09 October 1998\n" ); + printf ( " Reworking normal vector treatments.\n" ); + printf ( " Synchronizing IVREAD and IVCON.\n" ); + printf ( " POV_WRITE added.\n" ); + printf ( " 02 October 1998\n" ); + printf ( " IVCON reproduces BOX.3DS and CONE.3DS exactly.\n" ); + printf ( " 30 September 1998\n" ); + printf ( " IVCON compiled on the PC.\n" ); + printf ( " Interactive BYTE_SWAP option added for binary files.\n" ); + printf ( " 25 September 1998\n" ); + printf ( " OBJECT_NAME made available to store object name.\n" ); + printf ( " 23 September 1998\n" ); + printf ( " 3DS binary files can be written.\n" ); + printf ( " 15 September 1998\n" ); + printf ( " 3DS binary files can be read.\n" ); + printf ( " 01 September 1998\n" ); + printf ( " COR3_RANGE, FACE_NORMAL_AVE added.\n" ); + printf ( " Major modifications to normal vectors.\n" ); + printf ( " 24 August 1998\n" ); + printf ( " HRC_READ added.\n" ); + printf ( " 21 August 1998\n" ); + printf ( " TXT_WRITE improved.\n" ); + printf ( " 20 August 1998\n" ); + printf ( " HRC_WRITE can output lines as linear splines.\n" ); + printf ( " 19 August 1998\n" ); + printf ( " Automatic normal computation for OBJ files.\n" ); + printf ( " Added normal vector computation.\n" ); + printf ( " HRC_WRITE is working.\n" ); + printf ( " 18 August 1998\n" ); + printf ( " IV_READ/IV_WRITE handle BASECOLOR RGB properly now.\n" ); + printf ( " Improved treatment of face materials and normals.\n" ); + printf ( " 17 August 1998\n" ); + printf ( " ORDER_MAX increased to 35.\n" ); + printf ( " FACE_PRINT routine added.\n" ); + printf ( " INIT_DATA routine added.\n" ); + printf ( " 14 August 1998\n" ); + printf ( " IV_READ is working.\n" ); + printf ( " 13 August 1998\n" ); + printf ( " ASE_WRITE is working.\n" ); + printf ( " IV_WRITE is working.\n" ); + printf ( " 12 August 1998\n" ); + printf ( " ASE_READ is working.\n" ); + printf ( " 10 August 1998\n" ); + printf ( " DXF_WRITE is working.\n" ); + printf ( " DXF_READ is working.\n" ); + printf ( " 27 July 1998\n" ); + printf ( " Interactive mode is working.\n" ); + printf ( " OBJ_READ is working.\n" ); + printf ( " 25 July 1998\n" ); + printf ( " OBJ_WRITE is working.\n" ); + printf ( " 24 July 1998\n" ); + printf ( " DATA_CHECK checks the input data.\n" ); + printf ( " VLA_READ is working.\n" ); + printf ( " VLA_WRITE is working.\n" ); + printf ( " 23 July 1998\n" ); + printf ( " STL_WRITE is working.\n" ); + printf ( " 22 July 1998\n" ); + printf ( " STL_READ is working.\n" ); + printf ( " TXT_WRITE is working.\n" ); +} +/**********************************************************************/ + +void node_to_vertex_material ( void ) + +/**********************************************************************/ + +/* + Purpose: + + NODE_TO_VERTEX_MAT extends node material definitions to vertices. + + Discussion: + + A NODE is a point in space. + A VERTEX is a node as used in a particular face. + One node may be used as a vertex in several faces, or none. + + Modified: + + 22 May 1999 + + Author: + + John Burkardt +*/ +{ + int iface; + int ivert; + int node; + + for ( iface = 0; iface < face_num; iface++ ) { + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + node = face[ivert][iface]; + vertex_material[ivert][iface] = cor3_material[node]; + } + } + + return; +} +/******************************************************************************/ + +int obj_read ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + OBJ_READ reads a Wavefront OBJ file. + + Example: + + # magnolia.obj + + mtllib ./vp.mtl + + g + v -3.269770 -39.572201 0.876128 + v -3.263720 -39.507999 2.160890 + ... + v 0.000000 -9.988540 0.000000 + g stem + s 1 + usemtl brownskn + f 8 9 11 10 + f 12 13 15 14 + ... + f 788 806 774 + + Modified: + + 20 October 1998 + + Author: + + John Burkardt +*/ +{ + int count; + int i; + int ivert; + char *next; + char *next2; + char *next3; + int node; + int vertex_normal_num; + float r1; + float r2; + float r3; + char token[LINE_MAX_LEN]; + char token2[LINE_MAX_LEN]; + int width; +/* + Initialize. +*/ + vertex_normal_num = 0; +/* + Read the next line of the file into INPUT. +*/ + while ( fgets ( input, LINE_MAX_LEN, filein ) != NULL ) { + + text_num = text_num + 1; +/* + Advance to the first nonspace character in INPUT. +*/ + for ( next = input; *next != '\0' && isspace(*next); next++ ) { + } +/* + Skip blank lines and comments. +*/ + + if ( *next == '\0' ) { + continue; + } + + if ( *next == '#' || *next == '$' ) { + comment_num = comment_num + 1; + continue; + } +/* + Extract the first word in this line. +*/ + sscanf ( next, "%s%n", token, &width ); +/* + Set NEXT to point to just after this token. +*/ + + next = next + width; +/* + BEVEL + Bevel interpolation. +*/ + if ( leqi ( token, "BEVEL" ) == TRUE ) { + continue; + } +/* + BMAT + Basis matrix. +*/ + else if ( leqi ( token, "BMAT" ) == TRUE ) { + continue; + } +/* + C_INTERP + Color interpolation. +*/ + else if ( leqi ( token, "C_INTERP" ) == TRUE ) { + continue; + } +/* + CON + Connectivity between free form surfaces. +*/ + else if ( leqi ( token, "CON" ) == TRUE ) { + continue; + } +/* + CSTYPE + Curve or surface type. +*/ + else if ( leqi ( token, "CSTYPE" ) == TRUE ) { + continue; + } +/* + CTECH + Curve approximation technique. +*/ + else if ( leqi ( token, "CTECH" ) == TRUE ) { + continue; + } +/* + CURV + Curve. +*/ + else if ( leqi ( token, "CURV" ) == TRUE ) { + continue; + } +/* + CURV2 + 2D curve. +*/ + else if ( leqi ( token, "CURV2" ) == TRUE ) { + continue; + } +/* + D_INTERP + Dissolve interpolation. +*/ + else if ( leqi ( token, "D_INTERP" ) == TRUE ) { + continue; + } +/* + DEG + Degree. +*/ + else if ( leqi ( token, "DEG" ) == TRUE ) { + continue; + } +/* + END + End statement. +*/ + else if ( leqi ( token, "END" ) == TRUE ) { + continue; + } +/* + F V1 V2 V3 + or + F V1/VT1/VN1 V2/VT2/VN2 ... + or + F V1//VN1 V2//VN2 ... + + Face. + A face is defined by the vertices. + Optionally, slashes may be used to include the texture vertex + and vertex normal indices. + + OBJ line node indices are 1 based rather than 0 based. + So we have to decrement them before loading them into FACE. +*/ + + else if ( leqi ( token, "F" ) == TRUE ) { + + ivert = 0; + face_order[face_num] = 0; +/* + Read each item in the F definition as a token, and then + take it apart. +*/ + for ( ;; ) { + + count = sscanf ( next, "%s%n", token2, &width ); + next = next + width; + + if ( count != 1 ) { + break; + } + + count = sscanf ( token2, "%d%n", &node, &width ); + next2 = token2 + width; + + if ( count != 1 ) { + break; + } + + if ( ivert < ORDER_MAX && face_num < FACE_MAX ) { + face[ivert][face_num] = node-1; + vertex_material[ivert][face_num] = 0; + face_order[face_num] = face_order[face_num] + 1; + } +/* + If there's a slash, skip to the next slash, and extract the + index of the normal vector. +*/ + if ( *next2 == '/' ) { + + for ( next3 = next2 + 1; next3 < token2 + LINE_MAX_LEN; next3++ ) { + + if ( *next3 == '/' ) { + next3 = next3 + 1; + count = sscanf ( next3, "%d%n", &node, &width ); + + node = node - 1; + if ( 0 <= node && node < vertex_normal_num ) { + for ( i = 0; i < 3; i++ ) { + vertex_normal[i][ivert][face_num] = normal_temp[i][node]; + } + } + break; + } + } + } + ivert = ivert + 1; + } + face_num = face_num + 1; + } + +/* + G + Group name. +*/ + + else if ( leqi ( token, "G" ) == TRUE ) { + continue; + } +/* + HOLE + Inner trimming hole. +*/ + else if ( leqi ( token, "HOLE" ) == TRUE ) { + continue; + } +/* + L + I believe OBJ line node indices are 1 based rather than 0 based. + So we have to decrement them before loading them into LINE_DEX. +*/ + + else if ( leqi ( token, "L" ) == TRUE ) { + + for ( ;; ) { + + count = sscanf ( next, "%d%n", &node, &width ); + next = next + width; + + if ( count != 1 ) { + break; + } + + if ( line_num < LINES_MAX ) { + line_dex[line_num] = node-1; + line_material[line_num] = 0; + } + line_num = line_num + 1; + + } + + if ( line_num < LINES_MAX ) { + line_dex[line_num] = -1; + line_material[line_num] = -1; + } + line_num = line_num + 1; + + } + +/* + LOD + Level of detail. +*/ + else if ( leqi ( token, "LOD" ) == TRUE ) { + continue; + } +/* + MG + Merging group. +*/ + else if ( leqi ( token, "MG" ) == TRUE ) { + continue; + } +/* + MTLLIB + Material library. +*/ + + else if ( leqi ( token, "MTLLIB" ) == TRUE ) { + continue; + } +/* + O + Object name. +*/ + else if ( leqi ( token, "O" ) == TRUE ) { + continue; + } +/* + P + Point. +*/ + else if ( leqi ( token, "P" ) == TRUE ) { + continue; + } +/* + PARM + Parameter values. +*/ + else if ( leqi ( token, "PARM" ) == TRUE ) { + continue; + } +/* + S + Smoothing group +*/ + else if ( leqi ( token, "S" ) == TRUE ) { + continue; + } +/* + SCRV + Special curve. +*/ + else if ( leqi ( token, "SCRV" ) == TRUE ) { + continue; + } +/* + SHADOW_OBJ + Shadow casting. +*/ + else if ( leqi ( token, "SHADOW_OBJ" ) == TRUE ) { + continue; + } +/* + SP + Special point. +*/ + else if ( leqi ( token, "SP" ) == TRUE ) { + continue; + } +/* + STECH + Surface approximation technique. +*/ + else if ( leqi ( token, "STECH" ) == TRUE ) { + continue; + } +/* + STEP + Stepsize. +*/ + else if ( leqi ( token, "CURV" ) == TRUE ) { + continue; + } +/* + SURF + Surface. +*/ + else if ( leqi ( token, "SURF" ) == TRUE ) { + continue; + } +/* + TRACE_OBJ + Ray tracing. +*/ + else if ( leqi ( token, "TRACE_OBJ" ) == TRUE ) { + continue; + } +/* + TRIM + Outer trimming loop. +*/ + else if ( leqi ( token, "TRIM" ) == TRUE ) { + continue; + } +/* + USEMTL + Material name. +*/ + else if ( leqi ( token, "USEMTL" ) == TRUE ) { + continue; + } + +/* + V X Y Z W + Geometric vertex. + W is optional, a weight for rational curves and surfaces. + The default for W is 1. +*/ + + else if ( leqi ( token, "V" ) == TRUE ) { + + sscanf ( next, "%e %e %e", &r1, &r2, &r3 ); + + if ( cor3_num < COR3_MAX ) { + cor3[0][cor3_num] = r1; + cor3[1][cor3_num] = r2; + cor3[2][cor3_num] = r3; + } + + cor3_num = cor3_num + 1; + + } +/* + VN + Vertex normals. +*/ + + else if ( leqi ( token, "VN" ) == TRUE ) { + + sscanf ( next, "%e %e %e", &r1, &r2, &r3 ); + + if ( vertex_normal_num < ORDER_MAX * FACE_MAX ) { + normal_temp[0][vertex_normal_num] = r1; + normal_temp[1][vertex_normal_num] = r2; + normal_temp[2][vertex_normal_num] = r3; + } + + vertex_normal_num = vertex_normal_num + 1; + + } +/* + VT + Vertex texture. +*/ + else if ( leqi ( token, "VT" ) == TRUE ) { + continue; + } +/* + VP + Parameter space vertices. +*/ + else if ( leqi ( token, "VP" ) == TRUE ) { + continue; + } +/* + Unrecognized +*/ + else { + bad_num = bad_num + 1; + } + + } + return SUCCESS; +} +/******************************************************************************/ + +int obj_write ( FILE *fileout ) + +/******************************************************************************/ + +/* + Purpose: + + OBJ_WRITE writes a Wavefront OBJ file. + + Example: + + # magnolia.obj + + mtllib ./vp.mtl + + g + v -3.269770 -39.572201 0.876128 + v -3.263720 -39.507999 2.160890 + ... + v 0.000000 -9.988540 0.000000 + g stem + s 1 + usemtl brownskn + f 8 9 11 10 + f 12 13 15 14 + ... + f 788 806 774 + + Modified: + + 01 September 1998 + + Author: + + John Burkardt +*/ +{ + int i; + int iface; + int indexvn; + int ivert; + int k; + int new; + int text_num; + float w; +/* + Initialize. +*/ + text_num = 0; + w = 1.0; + + fprintf ( fileout, "# %s created by IVCON.\n", fileout_name ); + fprintf ( fileout, "# Original data in %s.\n", filein_name ); + fprintf ( fileout, "\n" ); + fprintf ( fileout, "g %s\n", object_name ); + fprintf ( fileout, "\n" ); + + text_num = text_num + 5; +/* + V: vertex coordinates. +*/ + for ( i = 0; i < cor3_num; i++ ) { + fprintf ( fileout, "v %f %f %f\n", + cor3[0][i], cor3[1][i], cor3[2][i]); + text_num = text_num + 1; + } + +/* + VN: Vertex face normal vectors. +*/ + if ( face_num > 0 ) { + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + } + + for ( iface = 0; iface < face_num; iface++ ) { + + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + + fprintf ( fileout, "vn %f %f %f\n", vertex_normal[0][ivert][iface], + vertex_normal[1][ivert][iface], vertex_normal[2][ivert][iface] ); + text_num = text_num + 1; + } + } +/* + F: faces. +*/ + if ( face_num > 0 ) { + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + } + + indexvn = 0; + + for ( iface = 0; iface < face_num; iface++ ) { + + fprintf ( fileout, "f" ); + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + indexvn = indexvn + 1; + fprintf ( fileout, " %d//%d", face[ivert][iface]+1, indexvn ); + } + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + } +/* + L: lines. +*/ + if ( line_num > 0 ) { + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + } + + new = TRUE; + + for ( i = 0; i < line_num; i++ ) { + + k = line_dex[i]; + + if ( k == -1 ) { + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + new = TRUE; + } + else { + if ( new == TRUE ) { + fprintf ( fileout, "l" ); + new = FALSE; + } + fprintf ( fileout, " %d", k+1 ); + } + + } + + fprintf ( fileout, "\n" ); + text_num = text_num + 1; +/* + Report. +*/ + printf ( "\n" ); + printf ( "OBJ_WRITE - Wrote %d text lines.\n", text_num ); + + return SUCCESS; +} +/******************************************************************************/ + +int pov_write ( FILE *fileout ) + +/******************************************************************************/ + +/* + Purpose: + + POV_WRITE writes graphics information to a POV file. + + Example: + + // cone.pov created by IVCON. + // Original data in cone.iv + + #version 3.0 + #include "colors.inc" + #include "shapes.inc" + global_settings { assumed_gamma 2.2 } + + camera { + right < 4/3, 0, 0> + up < 0, 1, 0 > + sky < 0, 1, 0 > + angle 20 + location < 0, 0, -300 > + look_at < 0, 0, 0> + } + + light_source { < 20, 50, -100 > color White } + + background { color SkyBlue } + + #declare RedText = texture { + pigment { color rgb < 0.8, 0.2, 0.2> } + finish { ambient 0.2 diffuse 0.5 } + } + + #declare BlueText = texture { + pigment { color rgb < 0.2, 0.2, 0.8> } + finish { ambient 0.2 diffuse 0.5 } + } + mesh { + smooth_triangle { + < 0.29, -0.29, 0.0>, < 0.0, 0.0, -1.0 >, + < 38.85, 10.03, 0.0>, < 0.0, 0.0, -1.0 >, + < 40.21, -0.29, 0.0>, < 0.0, 0.0, -1.0 > + texture { RedText } } + ... + smooth_triangle { + < 0.29, -0.29, 70.4142 >, < 0.0, 0.0, 1.0 >, + < 8.56, -2.51, 70.4142 >, < 0.0, 0.0, 1.0 >, + < 8.85, -0.29, 70.4142 >, < 0.0, 0.0, 1.0 > + texture { BlueText } } + } + + Modified: + + 08 October 1998 + + Author: + + John Burkardt +*/ +{ + int i; + int j; + int jj; + int jlo; + int k; + int text_num; + + text_num = 0; + fprintf ( fileout, "// %s created by IVCON.\n", fileout_name ); + fprintf ( fileout, "// Original data in %s.\n", filein_name ); + text_num = text_num + 2; +/* + Initial declarations. +*/ + fprintf ( fileout, "\n" ); + fprintf ( fileout, "#version 3.0\n" ); + fprintf ( fileout, "#include \"colors.inc\"\n" ); + fprintf ( fileout, "#include \"shapes.inc\"\n" ); + fprintf ( fileout, "global_settings { assumed_gamma 2.2 }\n" ); + fprintf ( fileout, "\n" ); + fprintf ( fileout, "camera {\n" ); + fprintf ( fileout, " right < 4/3, 0, 0>\n" ); + fprintf ( fileout, " up < 0, 1, 0 >\n" ); + fprintf ( fileout, " sky < 0, 1, 0 >\n" ); + fprintf ( fileout, " angle 20\n" ); + fprintf ( fileout, " location < 0, 0, -300 >\n" ); + fprintf ( fileout, " look_at < 0, 0, 0>\n" ); + fprintf ( fileout, "}\n" ); + fprintf ( fileout, "\n" ); + fprintf ( fileout, "light_source { < 20, 50, -100 > color White }\n" ); + fprintf ( fileout, "\n" ); + fprintf ( fileout, "background { color SkyBlue }\n" ); + + text_num = text_num + 15; +/* + Declare RGB textures. +*/ + fprintf ( fileout, "\n" ); + fprintf ( fileout, "#declare RedText = texture {\n" ); + fprintf ( fileout, " pigment { color rgb < 0.8, 0.2, 0.2> }\n" ); + fprintf ( fileout, " finish { ambient 0.2 diffuse 0.5 }\n" ); + fprintf ( fileout, "}\n" ); + fprintf ( fileout, "\n" ); + fprintf ( fileout, "#declare GreenText = texture {\n" ); + fprintf ( fileout, " pigment { color rgb < 0.2, 0.8, 0.2> }\n" ); + fprintf ( fileout, " finish { ambient 0.2 diffuse 0.5 }\n" ); + fprintf ( fileout, "}\n" ); + fprintf ( fileout, "\n" ); + fprintf ( fileout, "#declare BlueText = texture {\n" ); + fprintf ( fileout, " pigment { color rgb < 0.2, 0.2, 0.8> }\n" ); + fprintf ( fileout, " finish { ambient 0.2 diffuse 0.5 }\n" ); + fprintf ( fileout, "}\n" ); +/* + Write one big object. +*/ + fprintf ( fileout, "mesh {\n" ); + text_num = text_num + 1; +/* + Do the next face. +*/ + for ( i = 0; i < face_num; i++ ) { +/* + Break the face up into triangles, anchored at node 1. +*/ + for ( jlo = 0; jlo < face_order[i] - 2; jlo++ ) { + fprintf ( fileout, " smooth_triangle {\n" ); + text_num = text_num + 1; + + for ( j = jlo; j < jlo + 3; j++ ) { + + if ( j == jlo ) { + jj = 0; + } + else { + jj = j; + } + + k = face[jj][i]; + + fprintf ( fileout, "<%f, %f, %f>, <%f, %f, %f>", + cor3[0][k], cor3[1][k], cor3[2][k], + vertex_normal[0][jj][i], + vertex_normal[1][jj][i], + vertex_normal[2][jj][i] ); + + if ( j < jlo + 2 ) { + fprintf ( fileout, ",\n" ); + } + else { + fprintf ( fileout, "\n" ); + } + text_num = text_num + 1; + + } + + if (i%6 == 1 ) { + fprintf ( fileout, "texture { RedText } }\n" ); + } + else if ( i%2 == 0 ) { + fprintf ( fileout, "texture { BlueText } }\n" ); + } + else { + fprintf ( fileout, "texture { GreenText } }\n" ); + } + text_num = text_num + 1; + + } + + } + + fprintf ( fileout, "}\n" ); + text_num = text_num + 1; +/* + Report. +*/ + printf ( "\n" ); + printf ( "POV_WRITE - Wrote %d text lines.\n", text_num ); + + return SUCCESS; +} +/******************************************************************************/ + +int rcol_find ( float a[][COR3_MAX], int m, int n, float r[] ) + +/******************************************************************************/ + +/* + Purpose: + + RCOL_FIND finds if a vector occurs in a table. + + Comment: + + Explicitly forcing the second dimension to be COR3_MAX is a kludge. + I have to figure out how to do this as pointer references. + + Also, since the array is not sorted, this routine should not be carelessly + called repeatedly for really big values of N, because you'll waste a + lot of time. + + Modified: + + 27 April 1999 + + Author: + + John Burkardt +*/ +{ + int i; + int icol; + int j; + + icol = -1; + + for ( j = 0; j < n; j++ ) { + for ( i = 0; i < m; i++ ) { + if ( a[i][j] != r[i] ) { + break; + } + if ( i == m-1 ) { + return j; + } + } + } + + return icol; +} +/**********************************************************************/ + +float rgb_to_hue ( float r, float g, float b ) + +/**********************************************************************/ + +/* + Purpose: + + RGB_TO_HUE converts (R,G,B) colors to a hue value between 0 and 1. + + Discussion: + + The hue computed here should be the same as the H value computed + for HLS and HSV, except that it ranges from 0 to 1 instead of + 0 to 360. + + A monochromatic color ( white, black, or a shade of gray) does not + have a hue. This routine will return a special value of H = -1 + for such cases. + + Examples: + + Color R G B H + + red 1.0 0.0 0.0 0.00 + yellow 1.0 1.0 0.0 0.16 + green 0.0 1.0 0.0 0.33 + cyan 0.0 1.0 1.0 0.50 + blue 0.0 0.0 1.0 0.67 + magenta 1.0 0.0 1.0 0.83 + + black 0.0 0.0 0.0 -1.00 + gray 0.5 0.5 0.5 -1.00 + white 1.0 1.0 1.0 -1.00 + + Modified: + + 22 May 1999 + + Author: + + John Burkardt + + Parameters: + + Input, float R, G, B, the red, green and blue values of the color. + These values should be between 0 and 1. + + Output, float RGB_TO_HUE, the corresponding hue of the color, or -1.0 if + the color is monochromatic. +*/ +{ + float h; + float rgbmax; + float rgbmin; +/* + Make sure the colors are between 0 and 1. +*/ + if ( r < 0.0 ) { + r = 0.0; + } + else if ( r > 1.0 ) { + r = 1.0; + } + + if ( g < 0.0 ) { + g = 0.0; + } + else if ( g > 1.0 ) { + g = 1.0; + } + + if ( b < 0.0 ) { + b = 0.0; + } + else if ( b > 1.0 ) { + b = 1.0; + } +/* + Compute the minimum and maximum of R, G and B. +*/ + rgbmax = r; + if ( g > rgbmax ) { + rgbmax = g; + } + if ( b > rgbmax ) { + rgbmax = b; + } + + rgbmin = r; + if ( g < rgbmin ) { + rgbmin = g; + } + if ( b < rgbmin ) { + rgbmin = b; + } +/* + If RGBMAX = RGBMIN, { the color has no hue. +*/ + if ( rgbmax == rgbmin ) { + h = - 1.0; + } +/* + Otherwise, we need to determine the dominant color. +*/ + else { + + if ( r == rgbmax ) { + h = ( g - b ) / ( rgbmax - rgbmin ); + } + else if ( g == rgbmax ) { + h = 2.0 + ( b - r ) / ( rgbmax - rgbmin ); + } + else if ( b == rgbmax ) { + h = 4.0 + ( r - g ) / ( rgbmax - rgbmin ); + } + + h = h / 6.0; +/* + Make sure H lies between 0 and 1.0. +*/ + if ( h < 0.0 ) { + h = h + 1.0; + } + else if ( h > 1.0 ) { + h = h - 1.0; + } + + } + + return h; +} +/******************************************************************************/ + +short int short_int_read ( FILE *filein ) + +/******************************************************************************/ +/* + Purpose: + + SHORT_INT_READ reads a short int from a binary file. + + Modified: + + 14 October 1998 + + Author: + + John Burkardt +*/ +{ + unsigned char c1; + unsigned char c2; + short int ival; + + c1 = fgetc ( filein ); + c2 = fgetc ( filein ); + + ival = c1 | ( c2 << 8 ); + + return ival; +} +/******************************************************************************/ + +int short_int_write ( FILE *fileout, short int short_int_val ) + +/******************************************************************************/ + +/* + Purpose: + + SHORT_INT_WRITE writes a short int to a binary file. + + Modified: + + 14 October 1998 + + Author: + + John Burkardt +*/ +{ + union { + short int yint; + char ychar[2]; + } y; + + y.yint = short_int_val; + + if ( byte_swap == TRUE ) { + fputc ( y.ychar[1], fileout ); + fputc ( y.ychar[0], fileout ); + } + else { + fputc ( y.ychar[0], fileout ); + fputc ( y.ychar[1], fileout ); + } + + return 2; +} +/******************************************************************************/ + +int smf_read ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + SMF_READ reads an SMF file. + + Example: + + #SMF2.0 + # cube_face.smf + # This example demonstrates how an RGB color can be assigned to + # each face of an object. + # + # First, define the geometry of the cube. + # + v 0.0 0.0 0.0 + v 1.0 0.0 0.0 + v 0.0 1.0 0.0 + v 1.0 1.0 0.0 + v 0.0 0.0 1.0 + v 1.0 0.0 1.0 + v 0.0 1.0 1.0 + v 1.0 1.0 1.0 + f 1 4 2 + f 1 3 4 + f 5 6 8 + f 5 8 7 + f 1 2 6 + f 1 6 5 + f 2 4 8 + f 2 8 6 + f 4 3 7 + f 4 7 8 + f 3 1 5 + f 3 5 7 + # + # Colors will be bound 1 per face. + # + bind c face + c 1.0 0.0 0.0 + c 1.0 0.0 0.0 + c 0.0 1.0 0.0 + c 0.0 1.0 0.0 + c 0.0 0.0 1.0 + c 0.0 0.0 1.0 + c 1.0 1.0 0.0 + c 1.0 1.0 0.0 + c 0.0 1.0 1.0 + c 0.0 1.0 1.0 + c 1.0 0.0 1.0 + c 1.0 0.0 1.0 + # + # Normal vectors will be bound 1 per face. + # + bind n face + n 0.0 0.0 -1.0 + n 0.0 0.0 -1.0 + n 0.0 0.0 1.0 + n 0.0 0.0 1.0 + n 0.0 -1.0 0.0 + n 0.0 -1.0 0.0 + n 1.0 0.0 0.0 + n 1.0 0.0 0.0 + n 0.0 1.0 0.0 + n 0.0 1.0 0.0 + n -1.0 0.0 0.0 + n -1.0 0.0 0.0 + # + # Texture coordinate pairs will be bound 1 per face. + # + bind r face + r 0.0 0.0 + r 0.0 0.1 + r 0.0 0.2 + r 0.0 0.3 + r 0.1 0.0 + r 0.1 0.1 + r 0.1 0.2 + r 0.1 0.3 + r 0.2 0.0 + r 0.2 0.1 + r 0.2 0.2 + r 0.2 0.3 + + Modified: + + 03 July 1999 + + Author: + + John Burkardt +*/ +{ + float angle; + char axis; + float b; + char cnr[LINE_MAX_LEN]; + int count; + float dx; + float dy; + int face_count; + float g; + int icor3_normal; + int icor3_tex_uv; + int iface_normal; + int iface_tex_uv; + int imat; + int ivert; + int level; + char *next; + int node; + int node_count; + float r; + float r1; + float r2; + float r3; + float rgba[4]; + char *string; + float sx; + float sy; + float sz; + char token[LINE_MAX_LEN]; + char token2[LINE_MAX_LEN]; + char type[LINE_MAX_LEN]; + float u; + float v; + int vertex_base; + int vertex_correction; + int width; + float x; + float xvec[3]; + float y; + float z; + + face_count = 0; + icor3_normal = 0; + icor3_tex_uv = 0; + iface_normal = 0; + iface_tex_uv = 0; + level = 0; + node_count = 0; + vertex_base = 0; + vertex_correction = 0; +/* + Read the next line of the file into INPUT. +*/ + while ( fgets ( input, LINE_MAX_LEN, filein ) != NULL ) { + + text_num = text_num + 1; + + if ( debug ) { + printf ( "SMF_READ: DEBUG: Reading line #%d\n", text_num ); + } +/* + Advance to the first nonspace character in INPUT. +*/ + for ( next = input; *next != '\0' && isspace(*next); next++ ) { + } +/* + Skip blank lines. +*/ + + if ( *next == '\0' ) { + continue; + } +/* + Skip comment lines. +*/ + if ( *next == '#' || *next == '$' ) { + comment_num = comment_num + 1; + continue; + } +/* + Extract the first word in this line. +*/ + sscanf ( next, "%s%n", token, &width ); +/* + Set NEXT to point to just after this token. +*/ + next = next + width; +/* + BEGIN + Reset the transformation matrix to identity. + Node numbering starts at zero again. (Really, this is level based) + (Really should define a new transformation matrix, and concatenate.) + (Also, might need to keep track of level.) +*/ + if ( leqi ( token, "BEGIN" ) == TRUE ) { + + level = level + 1; + + vertex_base = cor3_num; + group_num = group_num + 1; + tmat_init ( transform_matrix ); + + } +/* + BIND [c|n|r] [vertex|face] + Specify the binding for RGB color, Normal, or Texture. + Options are "vertex" or "face" +*/ + else if ( leqi ( token, "BIND" ) == TRUE ) { + + sscanf ( next, "%s%n", cnr, &width ); + next = next + width; + + if ( debug ) { + printf ( "CNR = %s\n", cnr ); + } + + sscanf ( next, "%s%n", type, &width ); + next = next + width; + + if ( debug ) { + printf ( "TYPE = %s\n", type ); + } + + if ( leqi ( cnr, "C" ) == TRUE ) { + + if ( leqi ( type, "VERTEX" ) == TRUE ) { + strcpy ( material_binding, "PER_VERTEX" ); + } + else if ( leqi ( type, "FACE" ) == TRUE ) { + strcpy ( material_binding, "PER_FACE" ); + } + + } + else if ( leqi ( cnr, "N" ) == TRUE ) { + + if ( leqi ( type, "VERTEX" ) == TRUE ) { + strcpy ( normal_binding, "PER_VERTEX" ); + } + else if ( leqi ( type, "FACE" ) == TRUE ) { + strcpy ( normal_binding, "PER_FACE" ); + } + + } + else if ( leqi ( cnr, "R" ) == TRUE ) { + + if ( leqi ( type, "VERTEX" ) == TRUE ) { + strcpy ( texture_binding, "PER_VERTEX" ); + } + else if ( leqi ( type, "FACE" ) == TRUE ) { + strcpy ( texture_binding, "PER_FACE" ); + } + + } + + } +/* + C + Specify an RGB color, with R, G, B between 0.0 and 1.0. +*/ + else if ( leqi ( token, "C" ) == TRUE ) { + + sscanf ( next, "%f%n", &r, &width ); + next = next + width; + + sscanf ( next, "%f%n", &g, &width ); + next = next + width; + + sscanf ( next, "%f%n", &b, &width ); + next = next + width; +/* + Set up a temporary material (R,G,B,1.0). + Add the material to the material database, or find the index of + a matching material already in. + Assign the material of the node or face to this index. +*/ + rgba[0] = r; + rgba[1] = g; + rgba[2] = b; + rgba[3] = 1.0; + + if ( material_num < MATERIAL_MAX ) { + + for ( k = 0; k < 4; k++ ) { + material_rgba[k][material_num] = rgba[k]; + } + + imat = material_num; + material_num = material_num + 1; + + } + else { + + imat = 0; + + } + + if ( leqi ( material_binding, "PER_FACE" ) == TRUE ) { + + face_count = face_count + 1; + face_material[face_count] = imat; + + } + else if ( leqi ( material_binding, "PER_VERTEX" ) == TRUE ) { + + node_count = node_count + 1; + cor3_material[node_count] = imat; + + } + else { + + printf ( "\n" ); + printf ( "SMF_READ - Fatal error!\n" ); + printf ( " Material binding undefined!\n" ); + return ERROR; + + } + + } +/* + END + Drop down a level. +*/ + else if ( leqi ( token, "END" ) == TRUE ) { + + level = level - 1; + + if ( level < 0 ) { + printf ( "\n" ); + printf ( "SMF_READ - Fatal error!\n" ); + printf ( " More END statements than BEGINs!\n" ); + return ERROR; + } + } +/* + F V1 V2 V3 + + Face. + A face is defined by the vertices. + Node indices are 1 based rather than 0 based. + So we have to decrement them before loading them into FACE. + Note that vertex indices start back at 0 each time a BEGIN is entered. + The strategy here won't handle nested BEGIN's, just one at a time. +*/ + + else if ( leqi ( token, "F" ) == TRUE ) { + + ivert = 0; + face_order[face_num] = 0; +/* + Read each item in the F definition as a token, and then + take it apart. +*/ + for ( ;; ) { + + count = sscanf ( next, "%s%n", token2, &width ); + next = next + width; + + if ( count != 1 ) { + break; + } + + count = sscanf ( token2, "%d%n", &node, &width ); + + if ( count != 1 ) { + break; + } + + if ( ivert < ORDER_MAX && face_num < FACE_MAX ) { + face[ivert][face_num] = node - 1 + vertex_base; + vertex_material[ivert][face_num] = 0; + face_order[face_num] = face_order[face_num] + 1; + } + ivert = ivert + 1; + } + face_num = face_num + 1; + } +/* + N + Specify a normal vector. +*/ + else if ( leqi ( token, "N" ) == TRUE ) { + + sscanf ( next, "%f%n", &x, &width ); + next = next + width; + + sscanf ( next, "%f%n", &y, &width ); + next = next + width; + + sscanf ( next, "%f%n", &z, &width ); + next = next + width; + + if ( leqi ( normal_binding, "PER_FACE" ) == TRUE ) { + + face_normal[0][iface_normal] = x; + face_normal[1][iface_normal] = y; + face_normal[2][iface_normal] = z; + + iface_normal = iface_normal + 1; + + } + else if ( leqi ( normal_binding, "PER_VERTEX" ) == TRUE ) { + + cor3_normal[0][icor3_normal] = x; + cor3_normal[1][icor3_normal] = y; + cor3_normal[2][icor3_normal] = z; + + icor3_normal = icor3_normal + 1; + + } + else { + + printf ( "\n" ); + printf ( "SMF_READ - Fatal error!\n" ); + printf ( " Normal binding undefined!\n" ); + return ERROR; + + } + } +/* + R + Specify a texture coordinate. +*/ + else if ( leqi ( token, "R" ) == TRUE ) { + + sscanf ( next, "%f%n", &u, &width ); + next = next + width; + + sscanf ( next, "%f%n", &v, &width ); + next = next + width; + + if ( leqi ( texture_binding, "PER_FACE" ) == TRUE ) { + + face_tex_uv[0][iface_tex_uv] = u; + face_tex_uv[1][iface_tex_uv] = v; + + icor3_tex_uv = icor3_tex_uv + 1; + + } + else if ( leqi ( texture_binding, "PER_VERTEX" ) == TRUE ) { + + cor3_tex_uv[0][icor3_tex_uv] = u; + cor3_tex_uv[1][icor3_tex_uv] = v; + + icor3_tex_uv = icor3_tex_uv + 1; + } + else { + printf ( "\n" ); + printf ( "SMF_READ - Fatal error!\n" ); + printf ( " Texture binding undefined!\n" ); + return ERROR; + } + + } +/* + ROT [x|y|z] +*/ + else if ( leqi ( token, "ROT" ) == TRUE ) { + + sscanf ( next, "%c%n", &axis, &width ); + next = next + width; + + sscanf ( next, "%f%n", &angle, &width ); + next = next + width; + + tmat_rot_axis ( transform_matrix, transform_matrix, angle, axis ); + + } +/* + SCALE +*/ + else if ( leqi ( token, "SCALE" ) == TRUE ) { + + sscanf ( next, "%f%n", &sx, &width ); + next = next + width; + + sscanf ( next, "%f%n", &sy, &width ); + next = next + width; + + sscanf ( next, "%f%n", &sz, &width ); + next = next + width; + + tmat_scale ( transform_matrix, transform_matrix, sx, sy, sz ); + } +/* + SET VERTEX_CORRECTION + Specify increment to add to vertex indices in file. +*/ + else if ( leqi ( token, "SET" ) == TRUE ) { + + sscanf ( next, "%s%n", cnr, &width ); + next = next + width; + + sscanf ( next, "%d%n", &vertex_correction, &width ); + next = next + width; + + } +/* + T_SCALE + Specify a scaling to texture coordinates. +*/ + else if ( leqi ( token, "T_SCALE" ) == TRUE ) { + + sscanf ( next, "%f%n", &dx, &width ); + next = next + width; + + sscanf ( next, "%f%n", &dy, &width ); + next = next + width; + + } +/* + T_TRANS + Specify a translation to texture coordinates. +*/ + else if ( leqi ( token, "T_TRANS" ) == TRUE ) { + + sscanf ( next, "%f%n", &dx, &width ); + next = next + width; + + sscanf ( next, "%f%n", &dy, &width ); + next = next + width; + + } +/* + TEX + Specify a filename containing the texture. + (ANY CHANCE THIS IS RIGHT?) +*/ + else if ( leqi ( token, "TEX" ) == TRUE ) { + + sscanf ( next, "%s%n", string, &width ); + + for ( i = 0; i < LINE_MAX_LEN; i++ ) { + texture_name[texture_num][i] = string[i]; + if ( string[i] == '\0' ) { + break; + } + } + + texture_num = texture_num + 1; + + } +/* + TRANS +*/ + else if ( leqi ( token, "TRANS" ) == TRUE ) { + + sscanf ( next, "%f%n", &x, &width ); + next = next + width; + + sscanf ( next, "%f%n", &y, &width ); + next = next + width; + + sscanf ( next, "%f%n", &z, &width ); + next = next + width; + + tmat_trans ( transform_matrix, transform_matrix, x, y, z ); + } +/* + V X Y Z + Geometric vertex. +*/ + else if ( leqi ( token, "V" ) == TRUE ) { + + sscanf ( next, "%e %e %e", &r1, &r2, &r3 ); + + xvec[0] = r1; + xvec[1] = r2; + xvec[2] = r3; +/* + Apply current transformation matrix. + Right now, we can only handle one matrix, not a stack of + matrices representing nested BEGIN/END's. +*/ + tmat_mxp ( transform_matrix, xvec, xvec ); + + if ( cor3_num < COR3_MAX ) { + for ( i = 0; i < 3; i++ ) { + cor3[i][cor3_num] = xvec[i]; + } + } + + cor3_num = cor3_num + 1; + + } +/* + Unrecognized keyword. +*/ + else { + + bad_num = bad_num + 1; + + if ( bad_num <= 10 ) { + printf ( "\n" ); + printf ( "SMF_READ: Bad data on line %d.\n", text_num ); + } + } + + } +/* + Extend the material definition + * from the face to the vertices and nodes, or + * from the vertices to the faces and nodes. +*/ + if ( strcmp ( material_binding, "PER_FACE" ) == 0 ) { + + face_to_vertex_material ( ); + + vertex_to_node_material ( ); + + } + else if ( strcmp ( material_binding, "PER_VERTEX" ) == 0 ) { + + node_to_vertex_material ( ); + + vertex_to_face_material ( ); + + } + + return SUCCESS; +} +/******************************************************************************/ + +int smf_write ( FILE *fileout ) + +/******************************************************************************/ + +/* + Purpose: + + SMF_WRITE writes graphics information to an SMF file. + + Example: + + #SMF2.0 + # cube_face.smf + # This example demonstrates how an RGB color can be assigned to + # each face of an object. + # + # First, define the geometry of the cube. + # + v 0.0 0.0 0.0 + v 1.0 0.0 0.0 + v 0.0 1.0 0.0 + v 1.0 1.0 0.0 + v 0.0 0.0 1.0 + v 1.0 0.0 1.0 + v 0.0 1.0 1.0 + v 1.0 1.0 1.0 + f 1 4 2 + f 1 3 4 + f 5 6 8 + f 5 8 7 + f 1 2 6 + f 1 6 5 + f 2 4 8 + f 2 8 6 + f 4 3 7 + f 4 7 8 + f 3 1 5 + f 3 5 7 + # + # Colors will be bound 1 per face. + # + bind c face + c 1.0 0.0 0.0 + c 1.0 0.0 0.0 + c 0.0 1.0 0.0 + c 0.0 1.0 0.0 + c 0.0 0.0 1.0 + c 0.0 0.0 1.0 + c 1.0 1.0 0.0 + c 1.0 1.0 0.0 + c 0.0 1.0 1.0 + c 0.0 1.0 1.0 + c 1.0 0.0 1.0 + c 1.0 0.0 1.0 + # + # Normal vectors will be bound 1 per face. + # + bind n face + n 0.0 0.0 -1.0 + n 0.0 0.0 -1.0 + n 0.0 0.0 1.0 + n 0.0 0.0 1.0 + n 0.0 -1.0 0.0 + n 0.0 -1.0 0.0 + n 1.0 0.0 0.0 + n 1.0 0.0 0.0 + n 0.0 1.0 0.0 + n 0.0 1.0 0.0 + n -1.0 0.0 0.0 + n -1.0 0.0 0.0 + # + # Texture coordinate pairs will be bound 1 per face. + # + bind r face + r 0.0 0.0 + r 0.0 0.1 + r 0.0 0.2 + r 0.0 0.3 + r 0.1 0.0 + r 0.1 0.1 + r 0.1 0.2 + r 0.1 0.3 + r 0.2 0.0 + r 0.2 0.1 + r 0.2 0.2 + r 0.2 0.3 + + Modified: + + 05 July 1999 + + Author: + + John Burkardt +*/ +{ + int i; + int icor3; + int iface; + int imat; + int ivert; + int text_num; +/* + Initialize. +*/ + text_num = 0; + + fprintf ( fileout, "#$SMF 2.0\n" ); + fprintf ( fileout, "#$vertices %d\n", cor3_num ); + fprintf ( fileout, "#$faces %d\n", face_num ); + fprintf ( fileout, "#\n" ); + fprintf ( fileout, "# %s created by IVCON.\n", fileout_name ); + fprintf ( fileout, "# Original data in %s.\n", filein_name ); + fprintf ( fileout, "#\n" ); + + text_num = text_num + 7; +/* + V: vertex coordinates. +*/ + for ( i = 0; i < cor3_num; i++ ) { + fprintf ( fileout, "v %f %f %f\n", + cor3[0][i], cor3[1][i], cor3[2][i] ); + text_num = text_num + 1; + } +/* + F: faces. +*/ + if ( face_num > 0 ) { + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + } + + for ( iface = 0; iface < face_num; iface++ ) { + + fprintf ( fileout, "f" ); + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + fprintf ( fileout, " %d", face[ivert][iface]+1 ); + } + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + } +/* + Material binding. +*/ + fprintf ( fileout, "bind c vertex\n" ); + text_num = text_num + 1; +/* + Material RGB values at each node. +*/ + for ( icor3 = 0; icor3 < cor3_num; icor3++ ) { + + imat = cor3_material[icor3]; + + fprintf ( fileout, "c %f %f %f\n", material_rgba[0][imat], + material_rgba[1][imat], material_rgba[2][imat] ); + + text_num = text_num + 1; + } +/* + Normal binding. +*/ + fprintf ( fileout, "bind n vertex\n" ); + text_num = text_num + 1; +/* + Normal vector at each node. +*/ + for ( icor3 = 0; icor3 < cor3_num; icor3++ ) { + + fprintf ( fileout, "n %f %f %f\n", cor3_normal[0][icor3], + cor3_normal[1][icor3], cor3_normal[2][icor3] ); + + text_num = text_num + 1; + } + + if ( texture_num > 0 ) { +/* + Texture filename. +*/ + fprintf ( fileout, "tex %s\n", texture_name[0] ); + text_num = text_num + 1; +/* + Texture binding. +*/ + fprintf ( fileout, "bind r vertex\n" ); + text_num = text_num + 1; +/* + Texture coordinates at each node. +*/ + for ( icor3 = 0; icor3 < cor3_num; icor3++ ) { + fprintf ( fileout, "r %f %f\n", cor3_tex_uv[0][icor3], + cor3_tex_uv[1][icor3] ); + text_num = text_num + 1; + } + + } +/* + Report. +*/ + printf ( "\n" ); + printf ( "SMF_WRITE - Wrote %d text lines.\n", text_num ); + + return SUCCESS; +} +/******************************************************************************/ + +int stla_read ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + STLA_READ reads an ASCII STL (stereolithography) file. + + Examples: + + solid MYSOLID + facet normal 0.4 0.4 0.2 + outerloop + vertex 1.0 2.1 3.2 + vertex 2.1 3.7 4.5 + vertex 3.1 4.5 6.7 + endloop + endfacet + ... + facet normal 0.2 0.2 0.4 + outerloop + vertex 2.0 2.3 3.4 + vertex 3.1 3.2 6.5 + vertex 4.1 5.5 9.0 + endloop + endfacet + endsolid MYSOLID + + Modified: + + 20 October 1998 + + Author: + + John Burkardt +*/ +{ + int count; + int i; + int icor3; + int ivert; + char *next; + float r1; + float r2; + float r3; + float r4; + float temp[3]; + char token[LINE_MAX_LEN]; + int width; +/* + Read the next line of the file into INPUT. +*/ + while ( fgets ( input, LINE_MAX_LEN, filein ) != NULL ) { + + text_num = text_num + 1; +/* + Advance to the first nonspace character in INPUT. +*/ + for ( next = input; *next != '\0' && isspace(*next); next++ ) { + } +/* + Skip blank lines and comments. +*/ + if ( *next == '\0' || *next == '#' || *next == '!' || *next == '$' ) { + continue; + } +/* + Extract the first word in this line. +*/ + sscanf ( next, "%s%n", token, &width ); +/* + Set NEXT to point to just after this token. +*/ + next = next + width; +/* + FACET +*/ + if ( leqi ( token, "facet" ) == TRUE ) { +/* + Get the XYZ coordinates of the normal vector to the face. +*/ + sscanf ( next, "%*s %e %e %e", &r1, &r2, &r3 ); + + if ( face_num < FACE_MAX ) { + face_normal[0][face_num] = r1; + face_normal[1][face_num] = r2; + face_normal[2][face_num] = r3; + } + + fgets ( input, LINE_MAX_LEN, filein ); + text_num = text_num + 1; + + ivert = 0; + + for ( ;; ) { + + fgets ( input, LINE_MAX_LEN, filein ); + text_num = text_num + 1; + + count = sscanf ( input, "%*s %e %e %e", &r1, &r2, &r3 ); + + if ( count != 3 ) { + break; + } + + temp[0] = r1; + temp[1] = r2; + temp[2] = r3; + + if ( cor3_num < 1000 ) { + icor3 = rcol_find ( cor3, 3, cor3_num, temp ); + } + else { + icor3 = -1; + } + + if ( icor3 == -1 ) { + + icor3 = cor3_num; + + if ( cor3_num < COR3_MAX ) { + for ( i = 0; i < 3; i++ ) { + cor3[i][cor3_num] = temp[i]; + } + } + cor3_num = cor3_num + 1; + } + else { + dup_num = dup_num + 1; + } + + if ( ivert < ORDER_MAX && face_num < FACE_MAX ) { + face[ivert][face_num] = icor3; + vertex_material[ivert][face_num] = 0; + for ( i = 0; i < 3; i++ ) { + vertex_normal[i][ivert][face_num] = face_normal[i][face_num]; + } + } + + ivert = ivert + 1; + } + + fgets ( input, LINE_MAX_LEN, filein ); + text_num = text_num + 1; + + if ( face_num < FACE_MAX ) { + face_order[face_num] = ivert; + } + + face_num = face_num + 1; + + } +/* + COLOR +*/ + + else if ( leqi ( token, "color" ) == TRUE ) { + sscanf ( next, "%*s %f %f %f %f", &r1, &r2, &r3, &r4 ); + } +/* + SOLID +*/ + else if ( leqi ( token, "solid" ) == TRUE ) { + object_num = object_num + 1; + } +/* + ENDSOLID +*/ + else if ( leqi ( token, "endsolid" ) == TRUE ) { + } +/* + Unexpected or unrecognized. +*/ + else { + printf ( "\n" ); + printf ( "STLA_READ - Fatal error!\n" ); + printf ( " Unrecognized first word on line.\n" ); + return ERROR; + } + + } + return SUCCESS; +} +/******************************************************************************/ + +int stla_write ( FILE *fileout ) + +/******************************************************************************/ + +/* + Purpose: + + STLA_WRITE writes an ASCII STL (stereolithography) file. + + Examples: + + solid MYSOLID + facet normal 0.4 0.4 0.2 + outerloop + vertex 1.0 2.1 3.2 + vertex 2.1 3.7 4.5 + vertex 3.1 4.5 6.7 + endloop + endfacet + ... + facet normal 0.2 0.2 0.4 + outerloop + vertex 2.0 2.3 3.4 + vertex 3.1 3.2 6.5 + vertex 4.1 5.5 9.0 + endloop + endfacet + endsolid + + Discussion: + + The polygons in an STL file should only be triangular. This routine + will try to automatically decompose higher-order polygonal faces into + suitable triangles, without actually modifying the internal graphics + data. + + Modified: + + 01 September 1998 + + Author: + + John Burkardt +*/ +{ + int icor3; + int iface; + int jvert; + int face_num2; + int text_num; +/* + Initialize. +*/ + text_num = 0; + face_num2 = 0; + + fprintf ( fileout, "solid MYSOLID created by IVCON, original data in %s\n", + filein_name ); + + text_num = text_num + 1; + + for ( iface = 0; iface < face_num; iface++ ) { + + for ( jvert = 2; jvert < face_order[iface]; jvert++ ) { + + face_num2 = face_num2 + 1; + + fprintf ( fileout, " facet normal %f %f %f\n", + face_normal[0][iface], face_normal[1][iface], face_normal[2][iface] ); + + fprintf ( fileout, " outer loop\n" ); + + icor3 = face[0][iface]; + fprintf ( fileout, " vertex %f %f %f\n", + cor3[0][icor3], cor3[1][icor3], cor3[2][icor3] ); + + icor3 = face[jvert-1][iface]; + fprintf ( fileout, " vertex %f %f %f\n", + cor3[0][icor3], cor3[1][icor3], cor3[2][icor3] ); + + icor3 = face[jvert][iface]; + fprintf ( fileout, " vertex %f %f %f\n", + cor3[0][icor3], cor3[1][icor3], cor3[2][icor3] ); + + fprintf ( fileout, " endloop\n" ); + fprintf ( fileout, " endfacet\n" ); + text_num = text_num + 7; + } + } + + fprintf ( fileout, "endsolid MYSOLID\n" ); + text_num = text_num + 1; +/* + Report. +*/ + printf ( "\n" ); + printf ( "STLA_WRITE - Wrote %d text lines.\n", text_num ); + + if ( face_num != face_num2 ) { + printf ( " Number of faces in original data was %d.\n", face_num ); + printf ( " Number of triangular faces in decomposed data is %d.\n", + face_num2 ); + } + + return SUCCESS; +} +/******************************************************************************/ + +int stlb_read ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + STLB_READ reads a binary STL (stereolithography) file. + + Example: + + 80 byte string = header containing nothing in particular + + 4 byte int = number of faces + + For each face: + + 3 4-byte floats = components of normal vector to face; + 3 4-byte floats = coordinates of first node; + 3 4-byte floats = coordinates of second node; + 3 4-byte floats = coordinates of third and final node; + 2-byte int = attribute, whose value is 0. + + Modified: + + 24 May 1999 + + Author: + + John Burkardt +*/ +{ + short int attribute = 0; + char c; + float cvec[3]; + int icor3; + int i; + int iface; + int ivert; +/* + 80 byte Header. +*/ + for ( i = 0; i < 80; i++ ) { + c = char_read ( filein ); + if ( debug ) { + printf ( "%d\n", c ); + } + bytes_num = bytes_num + 1; + } +/* + Number of faces. +*/ + face_num = long_int_read ( filein ); + bytes_num = bytes_num + 4; +/* + For each (triangular) face, + components of normal vector, + coordinates of three vertices, + 2 byte "attribute". +*/ + for ( iface = 0; iface < face_num; iface++ ) { + + face_order[iface] = 3; + face_material[iface] = 0; + + for ( i = 0; i < 3; i++ ) { + face_normal[i][iface] = float_read ( filein ); + bytes_num = bytes_num + 4; + } + + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + + for ( i = 0; i < 3; i++ ) { + cvec[i] = float_read ( filein ); + bytes_num = bytes_num + 4; + } + + if ( cor3_num < 1000 ) { + icor3 = rcol_find ( cor3, 3, cor3_num, cvec ); + } + else { + icor3 = -1; + } + + if ( icor3 == -1 ) { + icor3 = cor3_num; + if ( cor3_num < COR3_MAX ) { + cor3[0][cor3_num] = cvec[0]; + cor3[1][cor3_num] = cvec[1]; + cor3[2][cor3_num] = cvec[2]; + } + cor3_num = cor3_num + 1; + } + else { + dup_num = dup_num + 1; + } + + face[ivert][iface] = icor3; + + } + attribute = short_int_read ( filein ); + if ( debug ) { + printf ( "ATTRIBUTE = %d\n", attribute ); + } + bytes_num = bytes_num + 2; + } + + return SUCCESS; +} +/******************************************************************************/ + +int stlb_write ( FILE *fileout ) + +/******************************************************************************/ + +/* + Purpose: + + STLB_WRITE writes a binary STL (stereolithography) file. + + Example: + + 80 byte string = header containing nothing in particular + + 4 byte int = number of faces + + For each face: + + 3 4-byte floats = components of normal vector to face; + 3 4-byte floats = coordinates of first node; + 3 4-byte floats = coordinates of second node; + 3 4-byte floats = coordinates of third and final node; + 2-byte int = attribute, whose value is 0. + + Discussion: + + The polygons in an STL file should only be triangular. This routine + will try to automatically decompose higher-order polygonal faces into + suitable triangles, without actually modifying the internal graphics + data. + + Modified: + + 24 May 1999 + + Author: + + John Burkardt +*/ +{ + short int attribute = 0; + char c; + int i; + int icor3; + int iface; + int jvert; + int face_num2; +/* + 80 byte Header. +*/ + for ( i = 0; i < 80; i++ ) { + c = ' '; + bytes_num = bytes_num + char_write ( fileout, c ); + } +/* + Number of faces. +*/ + face_num2 = 0; + for ( iface = 0; iface < face_num; iface++ ) { + face_num2 = face_num2 + face_order[iface] - 2; + } + + bytes_num = bytes_num + long_int_write ( fileout, face_num2 ); +/* + For each (triangular) face, + components of normal vector, + coordinates of three vertices, + 2 byte "attribute". +*/ + for ( iface = 0; iface < face_num; iface++ ) { + + for ( jvert = 2; jvert < face_order[iface]; jvert++ ) { + + for ( i = 0; i < 3; i++ ) { + bytes_num = bytes_num + float_write ( fileout, face_normal[i][iface] ); + } + + icor3 = face[0][iface]; + for ( i = 0; i < 3; i++ ) { + bytes_num = bytes_num + float_write ( fileout, cor3[i][icor3] ); + } + + icor3 = face[jvert-1][iface]; + for ( i = 0; i < 3; i++ ) { + bytes_num = bytes_num + float_write ( fileout, cor3[i][icor3] ); + } + + icor3 = face[jvert][iface]; + for ( i = 0; i < 3; i++ ) { + bytes_num = bytes_num + float_write ( fileout, cor3[i][icor3] ); + } + + bytes_num = bytes_num + short_int_write ( fileout, attribute ); + + } + + } +/* + Report. +*/ + printf ( "\n" ); + printf ( "STLB_WRITE - Wrote %d bytes.\n", bytes_num ); + + if ( face_num != face_num2 ) { + printf ( " Number of faces in original data was %d.\n", face_num ); + printf ( " Number of triangular faces in decomposed data is %d.\n", + face_num2 ); + } + + return SUCCESS; +} +/******************************************************************************/ + +void tds_pre_process ( void ) + +/******************************************************************************/ + +/* + Purpose: + + TDS_PRE_PROCESS divides the monolithic object into acceptably small pieces. + + Note: + + The 3DS binary format allows an unsigned short int for the number of + points, and number of faces in an object. This limits such quantities + to 65535. We have at least one interesting object with more faces + than that. So we need to tag faces and nodes somehow. + + Modified: + + 14 October 1998 + + Author: + + John Burkardt +*/ +{ +/* static unsigned short int BIG = 60000; */ + + return; +} +/******************************************************************************/ + +int tds_read ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + TDS_READ reads a 3D Studio MAX binary 3DS file. + + Modified: + + 20 October 1998 + + Author: + + John Burkardt +*/ +{ + unsigned long int chunk_begin; + unsigned long int chunk_end; + unsigned long int chunk_length; + unsigned long int chunk_length2; + unsigned long int position; + unsigned short int temp_int; + int version; + int views_read; +/* + Initialize. +*/ + views_read = 0; + + temp_int = tds_read_u_short_int ( filein ); + + if ( temp_int == 0x4d4d ) { + + if ( debug ) { + printf ( "TDS_READ: DEBUG: Read magic number %0X.\n", temp_int ); + } +/* + Move to 28 bytes from the beginning of the file. +*/ + position = 28; + fseek ( filein, ( long ) position, SEEK_SET ); + version = fgetc ( filein ); + + if ( version < 3 ) { + printf ( "\n" ); + printf ( "TDS_READ - Fatal error!\n" ); + printf ( " This routine can only read 3DS version 3 or later.\n" ); + printf ( " The input file is version %d.\n" ,version ); + return ERROR; + } + + if ( debug ) { + printf ( "TDS_READ: DEBUG: Version number is %d.\n", version ); + } +/* + Move to 2 bytes from the beginning of the file. + Set CURRENT_POINTER to the first byte of the chunk. + Set CHUNK_LENGTH to the number of bytes in the chunk. +*/ + chunk_begin = 0; + position = 2; + fseek ( filein, ( long ) position, SEEK_SET ); + + chunk_length = tds_read_u_long_int ( filein ); + position = 6; + + chunk_end = chunk_begin + chunk_length; + + if ( debug ) { + printf ( "TDS_READ:\n" ); + printf ( " Chunk begin = %lu.\n", chunk_begin ); + printf ( " Chunk length = %lu.\n", chunk_length ); + printf ( " Chunk end = %lu.\n", chunk_end ); + } + + while ( position + 2 < chunk_end ) { + + temp_int = tds_read_u_short_int ( filein ); + position = position + 2; + + if ( debug ) { + printf ( "TDS_READ: Short int = %0X, position = %lu.\n", temp_int, position ); + } + + if ( temp_int == 0x0002 ) { + if ( debug ) { + printf ( "TDS_READ: Read_Initial_Section:\n" ); + } + chunk_length2 = tds_read_u_long_int ( filein ); + position = position + 4; + position = position - 6 + chunk_length2; + fseek ( filein, ( long ) position, SEEK_SET ); + } + else if ( temp_int == 0x3d3d ) { + if ( debug ) { + printf ( "TDS_READ: Read_Edit_Section:\n" ); + } + position = position - 2; + position = position + tds_read_edit_section ( filein, &views_read ); + } + else if ( temp_int == 0xb000 ) { + if ( debug ) { + printf ( "TDS_READ: Read_Keyframe_Section:\n" ); + } + + position = position - 2; + position = position + tds_read_keyframe_section ( filein, &views_read ); + } + else { + printf ( "\n" ); + printf ( "TDS_READ - Fatal error!\n" ); + printf ( " Unexpected input, position = %lu.\n", position ); + printf ( " TEMP_INT = %hux\n", temp_int ); + return ERROR; + } + } + position = chunk_begin + chunk_length; + fseek ( filein, ( long ) position, SEEK_SET ); + } + else { + printf ( "\n" ); + printf ( "TDS_READ - Fatal error!\n" ); + printf ( " Could not find the main section tag.\n" ); + return ERROR; + } + + return SUCCESS; +} +/******************************************************************************/ + +unsigned long tds_read_ambient_section ( FILE *filein ) + +/******************************************************************************/ + +{ + unsigned long int current_pointer; + unsigned char end_found = FALSE; + int i; + long int pointer; + float rgb_val[3]; + unsigned short int temp_int; + unsigned long int temp_pointer; + unsigned long int teller; + unsigned char true_c_val[3]; + + current_pointer = ftell ( filein ) - 2; + temp_pointer = tds_read_u_long_int ( filein ); + teller = 6; + + while ( end_found == FALSE ) { + + temp_int = tds_read_u_short_int ( filein ); + teller = teller + 2; + + switch ( temp_int ) { + case 0x0010: + if ( debug ) { + printf ( " COLOR_F color definition section tag of %0X\n", + temp_int ); + } + for ( i = 0; i < 3; i++ ) { + rgb_val[i] = float_read ( filein ); + } + if ( debug ) { + printf ( "RGB_VAL = %f %f %f\n", rgb_val[0], rgb_val[1], rgb_val[2] ); + } + teller = teller + 3 * sizeof ( float ); + break; + case 0x0011: + if ( debug ) { + printf ( " COLOR_24 24 bit color definition section tag of %0X\n", + temp_int ); + } + + for ( i = 0; i < 3; i++ ) { + true_c_val[i] = fgetc ( filein ); + } + if ( debug ) { + printf ( "TRUE_C_VAL = %d %d %d\n", true_c_val[0], true_c_val[1], + true_c_val[2] ); + } + teller = teller + 3; + break; + default: + break; + } + + if ( teller >= temp_pointer ) { + end_found = TRUE; + } + + } + + pointer = ( long ) ( current_pointer + temp_pointer ); + fseek ( filein, pointer, SEEK_SET ); + + return ( temp_pointer ); +} +/******************************************************************************/ + +unsigned long tds_read_background_section ( FILE *filein ) + +/******************************************************************************/ + +{ + unsigned long int current_pointer; + unsigned char end_found = FALSE; + int i; + long int pointer; + float rgb_val[3]; + unsigned short int temp_int; + unsigned long int temp_pointer; + unsigned long int teller; + unsigned char true_c_val[3]; + + current_pointer = ftell ( filein ) - 2; + temp_pointer = tds_read_u_long_int ( filein ); + teller = 6; + + while ( end_found == FALSE ) { + + temp_int = tds_read_u_short_int ( filein ); + teller = teller + 2; + + switch ( temp_int ) { + case 0x0010: + if ( debug ) { + printf ( " COLOR_F RGB color definition section tag of %0X\n", + temp_int ); + } + for ( i = 0; i < 3; i++ ) { + rgb_val[i] = float_read ( filein ); + } + if ( debug ) { + printf ( "RGB_VAL = %f %f %f\n", rgb_val[0], rgb_val[1], rgb_val[2] ); + } + teller = teller + 3 * sizeof ( float ); + break; + case 0x0011: + if ( debug ) { + printf ( " COLOR_24 24 bit color definition section tag of %0X\n", + temp_int ); + } + + for ( i = 0; i < 3; i++ ) { + true_c_val[i] = fgetc ( filein ); + } + if ( debug ) { + printf ( "TRUE_C_VAL = %d %d %d\n", true_c_val[0], true_c_val[1], + true_c_val[2] ); + } + teller = teller + 3; + break; + default: + break; + } + + if ( teller >= temp_pointer ) { + end_found = TRUE; + } + + } + + pointer = ( long ) ( current_pointer + temp_pointer ); + fseek ( filein, pointer, SEEK_SET ); + + return ( temp_pointer ); +} +/******************************************************************************/ + +unsigned long tds_read_boolean ( unsigned char *boolean, FILE *filein ) + +/******************************************************************************/ + +{ + unsigned long current_pointer; + long int pointer; + unsigned long temp_pointer; + + current_pointer = ftell ( filein ) - 2; + temp_pointer = tds_read_u_long_int ( filein ); + + *boolean = fgetc ( filein ); + + pointer = ( long ) ( current_pointer + temp_pointer ); + fseek ( filein, pointer, SEEK_SET ); + + return ( temp_pointer ); +} +/******************************************************************************/ + +unsigned long tds_read_camera_section ( FILE *filein ) + +/******************************************************************************/ +{ + float camera_eye[3]; + float camera_focus[3]; + unsigned long int current_pointer; + float lens; + long int pointer; + float rotation; + unsigned long int temp_pointer; + unsigned short int u_short_int_val; + + current_pointer = ftell ( filein ) - 2; + temp_pointer = tds_read_u_long_int ( filein ); + + camera_eye[0] = float_read ( filein ); + camera_eye[1] = float_read ( filein ); + camera_eye[2] = float_read ( filein ); + + camera_focus[0] = float_read ( filein ); + camera_focus[1] = float_read ( filein ); + camera_focus[2] = float_read ( filein ); + + rotation = float_read ( filein ); + lens = float_read ( filein ); + + if ( debug ) { + printf ( " Found camera viewpoint at XYZ = %f %f %f.\n", + camera_eye[0], camera_eye[1], camera_eye[2] ); + printf ( " Found camera focus coordinates at XYZ = %f %f %f.\n", + camera_focus[0], camera_focus[1], camera_focus[2] ); + printf ( " Rotation of camera is: %f.\n", rotation ); + printf ( " Lens in used camera is: %f mm.\n", lens ); + } + + if ( ( temp_pointer-38 ) > 0 ) { + + if ( debug ) { + printf ( " Found extra camera sections.\n" ); + } + + u_short_int_val = tds_read_u_short_int ( filein ); + + if ( u_short_int_val == 0x4710 ) { + if ( debug ) { + printf ( " CAM_SEE_CONE.\n" ); + } + tds_read_unknown_section ( filein ); + } + + u_short_int_val = tds_read_u_short_int ( filein ); + + if ( u_short_int_val == 0x4720 ) { + if ( debug ) { + printf ( " CAM_RANGES.\n" ); + } + tds_read_unknown_section ( filein ); + } + + } + + pointer = ( long ) ( current_pointer + temp_pointer ); + fseek ( filein, pointer, SEEK_SET ); + + return ( temp_pointer ); +} +/******************************************************************************/ + +unsigned long tds_read_edit_section ( FILE *filein, int *views_read ) + +/******************************************************************************/ + +/* + Modified: + + 18 September 1998 +*/ +{ + unsigned long int chunk_length; + unsigned long int current_pointer; + unsigned char end_found = FALSE; + long int pointer; + unsigned long int teller; + unsigned short int temp_int; + + current_pointer = ftell ( filein ) - 2; + chunk_length = tds_read_u_long_int ( filein ); + teller = 6; + + while ( end_found == FALSE ) { + + temp_int = tds_read_u_short_int ( filein ); + teller = teller + 2; + + if ( debug ) { + printf ( " TDS_READ_EDIT_SECTION processing tag %0X\n", temp_int ); + } + + switch ( temp_int ) { + case 0x1100: + if ( debug ) { + printf ( " BIT_MAP section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0x1201: + if ( debug ) { + printf ( " USE_SOLID_BGND section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0x1300: + if ( debug ) { + printf ( " V_GRADIENT section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0x1400: + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0x1420: + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0x1450: + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0x1500: + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0x2200: + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0x2201: + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0x2210: + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0x2300: + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0x2302: + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0x3000: + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0x2100: + if ( debug ) { + printf ( " AMBIENT_LIGHT section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_ambient_section ( filein ); + break; + case 0x1200: + if ( debug ) { + printf ( " SOLID_BGND section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_background_section ( filein ); + break; + case 0x0100: + if ( debug ) { + printf ( " MASTER_SCALE section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0x3d3e: + if ( debug ) { + printf ( " MESH_VERSION section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xafff: + if ( debug ) { + printf ( " MAT_ENTRY section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_material_section ( filein ); + break; + case 0x4000: + if ( debug ) { + printf ( " NAMED_OBJECT section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_object_section ( filein ); + break; + case 0x7001: + if ( debug ) { + printf ( " VIEWPORT_LAYOUT section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_view_section ( filein, views_read ); + break; + case 0x7012: + if ( debug ) { + printf ( " VIEWPORT_DATA_3 section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0x7011: + if ( debug ) { + printf ( " VIEWPORT_DATA section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0x7020: + if ( debug ) { + printf ( " VIEWPORT_SIZE section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + default: + if ( debug ) { + printf ( " Junk.\n" ); + } + break; + } + + if ( teller >= chunk_length ) { + end_found = TRUE; + } + + } + + pointer = ( long ) ( current_pointer + chunk_length ); + + fseek ( filein, pointer, SEEK_SET ); + + return ( chunk_length ); +} +/******************************************************************************/ + +unsigned long tds_read_keyframe_section ( FILE *filein, int *views_read ) + +/******************************************************************************/ +{ + unsigned long int current_pointer; + unsigned char end_found = FALSE; + long int pointer; + unsigned short int temp_int; + unsigned long int temp_pointer; + unsigned long int teller; + + current_pointer = ftell ( filein ) - 2; + temp_pointer = tds_read_u_long_int ( filein ); + teller = 6; + + while ( end_found == FALSE ) { + + temp_int = tds_read_u_short_int ( filein ); + teller = teller + 2; + + switch ( temp_int ) { + case 0x7001: + if ( debug ) { + printf ( " VIEWPORT_LAYOUT main definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_view_section ( filein, views_read ); + break; + case 0xb008: + if ( debug ) { + printf ( " KFSEG frames section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xb002: + if ( debug ) { + printf ( " OBJECT_NODE_TAG object description section tag of %0X\n", + temp_int); + } + teller = teller + tds_read_keyframe_objdes_section ( filein ); + break; + case 0xb009: + if ( debug ) { + printf ( " KFCURTIME section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xb00a: + if ( debug ) { + printf ( " KFHDR section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + default: + break; + } + + if ( teller >= temp_pointer ) { + end_found = TRUE; + } + + } + + pointer = ( long ) ( current_pointer + temp_pointer ); + fseek ( filein, pointer, SEEK_SET ); + + return ( temp_pointer ); +} +/******************************************************************************/ + +unsigned long tds_read_keyframe_objdes_section ( FILE *filein ) + +/******************************************************************************/ + +/* + Modified: + + 21 September 1998 +*/ +{ + unsigned long int chunk_size; + unsigned long int current_pointer; + unsigned char end_found = FALSE; + long int pointer; + unsigned short int temp_int; + unsigned long int temp_pointer; + unsigned long int teller; + unsigned long int u_long_int_val; + unsigned short int u_short_int_val; + + current_pointer = ftell ( filein ) - 2; + temp_pointer = tds_read_u_long_int ( filein ); + teller = 6; + + while ( end_found == FALSE ) { + + temp_int = tds_read_u_short_int ( filein ); + teller = teller + 2; + + switch ( temp_int ) { + case 0xb011: + if ( debug ) { + printf ( " INSTANCE_NAME section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xb010: + if ( debug ) { + printf ( " NODE_HDR section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xb020: + if ( debug ) { + printf ( " POS_TRACK_TAG section tag of %0X\n", temp_int ); + } + chunk_size = tds_read_u_long_int ( filein ); + if ( debug ) { + printf ( " chunk_size = %d\n", chunk_size ); + } + u_short_int_val = tds_read_u_short_int ( filein ); + u_short_int_val = tds_read_u_short_int ( filein ); + u_short_int_val = tds_read_u_short_int ( filein ); + u_short_int_val = tds_read_u_short_int ( filein ); + u_short_int_val = tds_read_u_short_int ( filein ); + u_short_int_val = tds_read_u_short_int ( filein ); + u_short_int_val = tds_read_u_short_int ( filein ); + u_short_int_val = tds_read_u_short_int ( filein ); + u_long_int_val = tds_read_u_long_int ( filein ); + if ( debug ) { + printf ( "u_short_int_val = %d\n", u_short_int_val ); + printf ( "u_long_int_val = %d\n", u_long_int_val ); + } + origin[0] = float_read ( filein ); + origin[1] = float_read ( filein ); + origin[2] = float_read ( filein ); + teller = teller + 32; + break; + case 0xb013: + if ( debug ) { + printf ( " PIVOT section tag of %0X\n", temp_int ); + } + chunk_size = tds_read_u_long_int ( filein ); + pivot[0] = float_read ( filein ); + pivot[1] = float_read ( filein ); + pivot[2] = float_read ( filein ); + teller = teller + 12; + break; + case 0xb014: + if ( debug ) { + printf ( " BOUNDBOX section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xb015: + if ( debug ) { + printf ( " MORPH_SMOOTH section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xb021: + if ( debug ) { + printf ( " ROT_TRACK_TAG section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xb022: + if ( debug ) { + printf ( " SCL_TRACK_TAG section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xb030: + if ( debug ) { + printf ( " NODE_ID section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + default: + break; + } + + if ( teller >= temp_pointer ) { + end_found = TRUE; + } + + } + + pointer = ( long ) ( current_pointer+temp_pointer ); + fseek ( filein, pointer, SEEK_SET ); + + return ( temp_pointer ); +} +/******************************************************************************/ + +unsigned long tds_read_light_section ( FILE *filein ) + +/******************************************************************************/ +{ + unsigned char boolean; + unsigned long int current_pointer; + unsigned char end_found = FALSE; + int i; + float light_coors[3]; + long int pointer; + float rgb_val[3]; + unsigned long int teller; + unsigned short int temp_int; + unsigned long int temp_pointer; + unsigned char true_c_val[3]; + + current_pointer = ftell ( filein ) - 2; + temp_pointer = tds_read_u_long_int ( filein ); + teller = 6; + + light_coors[0] = float_read ( filein ); + light_coors[1] = float_read ( filein ); + light_coors[2] = float_read ( filein ); + + teller = teller + 3 * 4; + + if ( debug ) { + printf ( " Found light at coordinates XYZ = %f %f %f.\n", + light_coors[0], light_coors[1], light_coors[2] ); + } + + while ( end_found == FALSE ) { + + temp_int = tds_read_u_short_int ( filein ); + teller = teller + 2; + + switch ( temp_int ) { + case 0x0010: + if ( debug ) { + printf ( " COLOR_F RGB color definition section tag of %0X\n", + temp_int ); + } + for ( i = 0; i < 3; i++ ) { + rgb_val[i] = float_read ( filein ); + } + if ( debug ) { + printf ( " RGB_VAL value set to %f %f %f\n", rgb_val[0], + rgb_val[1], rgb_val[2] ); + } + teller = teller + 3 * sizeof ( float ); + break; + case 0x0011: + if ( debug ) { + printf ( " COLOR_24 24 bit color definition section tag of %0X\n", + temp_int ); + } + + for ( i = 0; i < 3; i++ ) { + true_c_val[i] = fgetc ( filein ); + } + if ( debug ) { + printf ( " TRUE_C_VAL value set to %d %d %d\n", true_c_val[0], + true_c_val[1], true_c_val[2] ); + } + teller = teller + 3; + break; + case 0x4620: + if ( debug ) { + printf ( " DL_OFF section: %0X\n", temp_int ); + } + teller = teller + tds_read_boolean ( &boolean, filein ); + if ( debug ) { + if ( boolean == TRUE ) { + printf ( " Light is on\n" ); + } + else { + printf ( " Light is off\n" ); + } + } + break; + case 0x4610: + if ( debug ) { + printf ( " DL_SPOTLIGHT section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_spot_section ( filein ); + break; + case 0x465a: + if ( debug ) { + printf ( " DL_OUTER_RANGE section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + default: + break; + } + + if ( teller >= temp_pointer ) { + end_found = TRUE; + } + + } + + pointer = ( long ) ( current_pointer + temp_pointer ); + fseek ( filein, pointer, SEEK_SET ); + + return ( temp_pointer ); +} +/******************************************************************************/ + +unsigned long int tds_read_u_long_int ( FILE *filein ) + +/******************************************************************************/ + +/* + Modified: + + 01 October 1998 + + Author: + + John Burkardt +*/ +{ + union { + unsigned long int yint; + char ychar[4]; + } y; + + if ( byte_swap == TRUE ) { + y.ychar[3] = fgetc ( filein ); + y.ychar[2] = fgetc ( filein ); + y.ychar[1] = fgetc ( filein ); + y.ychar[0] = fgetc ( filein ); + } + else { + y.ychar[0] = fgetc ( filein ); + y.ychar[1] = fgetc ( filein ); + y.ychar[2] = fgetc ( filein ); + y.ychar[3] = fgetc ( filein ); + } + + return y.yint; +} +/******************************************************************************/ + +int tds_read_long_name ( FILE *filein ) + +/******************************************************************************/ +{ + unsigned char letter; + unsigned int teller; + + teller = 0; + letter = fgetc ( filein ); +/* + Could be a dummy object. +*/ + if ( letter == 0 ) { + strcpy ( temp_name, "Default_name" ); + return -1; + } + + temp_name[teller] = letter; + teller = teller + 1; + + do { + letter = fgetc ( filein ); + temp_name[teller] = letter; + teller = teller + 1; + } while ( letter != 0 ); + + temp_name[teller-1] = 0; + + if ( debug ) { + printf ( " tds_read_long_name found name: %s.\n", temp_name ); + } + + return teller; +} +/******************************************************************************/ + +unsigned long tds_read_matdef_section ( FILE *filein ) + +/******************************************************************************/ +{ + unsigned long int current_pointer; + long int pointer; + int teller; + unsigned long int temp_pointer; + + current_pointer = ftell ( filein ) - 2; + temp_pointer = tds_read_u_long_int ( filein ); + + teller = tds_read_long_name ( filein ); + + if ( teller == -1 ) { + if ( debug ) { + printf ( " No material name found.\n" ); + } + } + else { + strcpy ( mat_name, temp_name ); + if ( debug ) { + printf ( " Material name %s.\n", mat_name ); + } + } + + pointer = ( long ) ( current_pointer + temp_pointer ); + fseek ( filein, pointer, SEEK_SET ); + + return ( temp_pointer ); +} +/******************************************************************************/ + +unsigned long tds_read_material_section ( FILE *filein ) + +/******************************************************************************/ +{ + unsigned long int current_pointer; + unsigned char end_found = FALSE; + long int pointer; + unsigned short int temp_int; + unsigned long int temp_pointer; + unsigned long int teller; + + current_pointer = ftell ( filein ) - 2; + + temp_pointer = tds_read_u_long_int ( filein ); + teller = 6; + + while ( end_found == FALSE ) { + + temp_int = tds_read_u_short_int ( filein ); + teller = teller + 2; + + switch ( temp_int ) { + + case 0xa000: + if ( debug ) { + printf ( " MAT_NAME definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_matdef_section ( filein ); + break; + case 0xa010: + if ( debug ) { + printf ( " MAT_AMBIENT definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa020: + if ( debug ) { + printf ( " MAT_DIFFUSE definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa030: + if ( debug ) { + printf ( " MAT_SPECULAR definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa040: + if ( debug ) { + printf ( " MAT_SHININESS definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa041: + if ( debug ) { + printf ( " MAT_SHIN2PCT definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa042: + if ( debug ) { + printf ( " MAT_SHIN3PCT definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa050: + if ( debug ) { + printf ( " MAT_TRANSPARENCY definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa052: + if ( debug ) { + printf ( " MAT_XPFALL definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa053: + if ( debug ) { + printf ( " MAT_REFBLUR definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa080: + if ( debug ) { + printf ( " MAT_SELF_ILLUM definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa081: + if ( debug ) { + printf ( " MAT_TWO_SIDE definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa082: + if ( debug ) { + printf ( " MAT_DECAL definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa083: + if ( debug ) { + printf ( " MAT_ADDITIVE definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa084: + if ( debug ) { + printf ( " MAT_SELF_ILPCT definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa085: + if ( debug ) { + printf ( " MAT_WIRE definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa086: + if ( debug ) { + printf ( " MAT_SUPERSMP definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa087: + if ( debug ) { + printf ( " MAT_WIRESIZE definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa088: + if ( debug ) { + printf ( " MAT_FACEMAP definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa08a: + if ( debug ) { + printf ( " MAT_XPFALLIN definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa08c: + if ( debug ) { + printf ( " MAT_PHONGSOFT definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa08e: + if ( debug ) { + printf ( " MAT_WIREABS definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa100: + if ( debug ) { + printf ( " MAT_SHADING definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa200: + if ( debug ) { + printf ( " MAT_TEXMAP definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_texmap_section ( filein ); +/* + teller = teller + tds_read_unknown_section ( filein ); +*/ + break; + case 0xa204: + if ( debug ) { + printf ( " MAT_SPECMAP definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa210: + if ( debug ) { + printf ( " MAT_OPACMAP definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa220: + if ( debug ) { + printf ( " MAT_REFLMAP definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa230: + if ( debug ) { + printf ( " MAT_BUMPMAP definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0xa353: + if ( debug ) { + printf ( " MAT_MAP_TEXBLUR definition section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + default: + if ( debug ) { + printf ( " Junk section tag of %0X\n", temp_int ); + } + break; + } + + if ( teller >= temp_pointer ) { + end_found = TRUE; + } + + } + pointer = ( long ) ( current_pointer + temp_pointer ); + + fseek ( filein, pointer, SEEK_SET ); + + return ( temp_pointer ); +} +/******************************************************************************/ + +int tds_read_name ( FILE *filein ) + +/******************************************************************************/ +{ + unsigned char letter; + unsigned int teller; + + teller = 0; + letter = fgetc ( filein ); +/* + Could be a dummy object. +*/ + + if ( letter == 0 ) { + strcpy ( temp_name, "Default name" ); + return (-1); + } + + temp_name[teller] = letter; + teller = teller + 1; + + do { + letter = fgetc ( filein ); + temp_name[teller] = letter; + teller = teller + 1; + } while ( ( letter != 0 ) && ( teller < 12 ) ); + + temp_name[teller-1] = 0; + + if ( debug ) { + printf ( " tds_read_name found name: %s.\n", temp_name ); + } + + return 0; +} +/******************************************************************************/ + +unsigned long tds_read_obj_section ( FILE *filein ) + +/******************************************************************************/ + +/* + Comments: + + Thanks to John F Flanagan for some suggested corrections. + + Modified: + + 30 June 2001 +*/ +{ + unsigned short int b; + unsigned long int chunk_size; + unsigned short int color_index; + unsigned long int current_pointer; + unsigned char end_found = FALSE; + unsigned short int g; + int i; + int j; + int cor3_num_base; + int cor3_num_inc; + int face_num_inc; + long int pointer; + unsigned short int r; + unsigned short int temp_int; + unsigned long int temp_pointer; + unsigned long int temp_pointer2; + unsigned long int teller; + + current_pointer = ftell ( filein ) - 2; + temp_pointer = tds_read_u_long_int ( filein ); + teller = 6; + cor3_num_base = cor3_num; + + while ( end_found == FALSE ) { + + temp_int = tds_read_u_short_int ( filein ); + teller = teller + 2; + + switch ( temp_int ) { + + case 0x4000: + if ( debug ) { + printf ( " NAMED_OBJECT section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + + case 0x4100: + if ( debug ) { + printf ( " N_TRI_OBJECT section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + + case 0x4110: + + if ( debug ) { + printf ( " POINT_ARRAY section tag of %0X\n", temp_int ); + } + + current_pointer = ftell ( filein ) - 2; + temp_pointer2 = tds_read_u_long_int ( filein ); + cor3_num_inc = ( int ) tds_read_u_short_int ( filein ); + + for ( i = cor3_num; i < cor3_num + cor3_num_inc; i++ ) { + cor3[0][i] = float_read ( filein ); + cor3[1][i] = float_read ( filein ); + cor3[2][i] = float_read ( filein ); + } + + cor3_num = cor3_num + cor3_num_inc; + teller = teller + temp_pointer2; + break; + + case 0x4111: + if ( debug ) { + printf ( " POINT_FLAG_ARRAY faces (2) section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + + case 0x4120: + + if ( debug ) { + printf ( " FACE_ARRAY section tag of %0X\n", + temp_int ); + } + + temp_pointer2 = tds_read_u_long_int ( filein ); + face_num_inc = ( int ) tds_read_u_short_int ( filein ); + + for ( i = face_num; i < face_num + face_num_inc; i++ ) { + face[0][i] = tds_read_u_short_int ( filein ) + cor3_num_base; + face[1][i] = tds_read_u_short_int ( filein ) + cor3_num_base; + face[2][i] = tds_read_u_short_int ( filein ) + cor3_num_base; + face_order[i] = 3; + face_flags[i] = tds_read_u_short_int ( filein ); +/* + Color is given per face, and as 24 bit RGB data packed in one word. + Extract RGB from the word, and assign R / 255 to each vertex. + + Just a guess, JVB, 30 June 2001. +*/ + temp_int = face_flags[i] & 0x000F; + r = ( temp_int & 0x0004 ) >> 2; + g = ( temp_int & 0x0002 ) >> 1; + b = ( temp_int & 0x0001 ); + + for ( j = 0; j < 3; j++ ) { + vertex_rgb[0][j][i] = ( float ) r / 255.0; + vertex_rgb[1][j][i] = ( float ) g / 255.0; + vertex_rgb[2][j][i] = ( float ) b / 255.0; + } + + } + + temp_int = tds_read_u_short_int ( filein ); + if ( temp_int == 0x4150 ) { + for ( i = face_num; i < face_num + face_num_inc; i++ ) { + face_smooth[i] = ( int ) tds_read_u_long_int ( filein ) + + cor3_num_base; + } + } + face_num = face_num + face_num_inc; + teller = ftell ( filein ); + break; + + case 0x4130: + if ( debug ) { + printf ( " MSH_MAT_GROUP section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + + case 0x4140: + if ( debug ) { + printf ( " TEX_VERTS section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_tex_verts_section ( filein ); + break; + + case 0x4150: + if ( debug ) { + printf ( " SMOOTH_GROUP section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + + case 0x4160: + + if ( debug ) { + printf ( " MESH_MATRIX section tag of %0X\n", + temp_int ); + } + + tds_read_u_long_int ( filein ); + + for ( j = 0; j < 4; j++ ) { + for ( i = 0; i < 3; i++ ) { + transform_matrix[j][i] = float_read ( filein ); + } + } + transform_matrix[0][3] = 0.0; + transform_matrix[1][3] = 0.0; + transform_matrix[2][3] = 0.0; + transform_matrix[3][3] = 0.0; + + teller = teller + 12 * sizeof ( float ); + break; + + case 0x4165: + + if ( debug ) { + printf ( " MESH_COLOR section tag of %0X\n", temp_int ); + } + + chunk_size = tds_read_u_long_int ( filein ); + + if ( chunk_size == 7 ) { + color_index = fgetc ( filein ); + teller = teller + 5; + } + else { + color_index = tds_read_u_short_int ( filein ); + teller = teller + 6; + } + if ( debug ) { + printf ( " Color index set to %d\n", color_index ); + } + break; + + case 0x4170: + if ( debug ) { + printf ( " MESH_TEXTURE_INFO section tag of %0X\n", + temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + + default: + if ( debug ) { + printf ( " JUNK section tag of %0X\n", temp_int ); + } + break; + } + + if ( teller >= temp_pointer ) { + end_found = TRUE; + } + + } + + pointer = ( long int ) ( current_pointer + temp_pointer ); + fseek ( filein, pointer, SEEK_SET ); + + return ( temp_pointer ); +} +/******************************************************************************/ + +unsigned long tds_read_object_section ( FILE *filein ) + +/******************************************************************************/ +{ + unsigned char end_found = FALSE; + unsigned long int current_pointer; + int int_val; + long int pointer; + unsigned short int temp_int; + unsigned long int temp_pointer; + unsigned long int teller; + + current_pointer = ftell ( filein ) - 2; + temp_pointer = tds_read_u_long_int ( filein ); + teller = 6; +/* + Why don't you read and save the name here? +*/ + int_val = tds_read_name ( filein ); + + if ( int_val == -1 ) { + if ( debug ) { + printf ( " Dummy Object found\n" ); + } + } + else { + strcpy ( object_name, temp_name ); + } + + while ( end_found == FALSE ) { + + temp_int = tds_read_u_short_int ( filein ); + teller = teller + 2; + + switch ( temp_int ) { + case 0x4700: + if ( debug ) { + printf ( " N_CAMERA section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_camera_section ( filein ); + break; + case 0x4600: + if ( debug ) { + printf ( " N_DIRECT_LIGHT section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_light_section ( filein ); + break; + case 0x4100: + if ( debug ) { + printf ( " OBJ_TRIMESH section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_obj_section ( filein ); + break; + case 0x4010: + if ( debug ) { + printf ( " OBJ_HIDDEN section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0x4012: + if ( debug ) { + printf ( " OBJ_DOESNT_CAST section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + default: + break; + } + + if ( teller >= temp_pointer ) { + end_found = TRUE; + } + + } + + pointer = ( long ) ( current_pointer + temp_pointer ); + + fseek ( filein, pointer, SEEK_SET ); + + return ( temp_pointer ); +} +/******************************************************************************/ + +unsigned long int tds_read_tex_verts_section ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + TDS_READ_TEX_VERTS_SECTION reads the texture vertex data. + + Discussion: + + The texture vertex data seems to be associated with nodes. This routine + distributes that data to vertices (nodes as they make up a particular + face). + + Modified: + + 02 July 1999 + + Author: + + John Burkardt +*/ +{ + unsigned long int current_pointer; + int icor3; + long int pointer; + unsigned long int temp_pointer; + unsigned short int n2; + + current_pointer = ftell ( filein ) - 2; + temp_pointer = tds_read_u_long_int ( filein ); + + pointer = ( long int ) ( current_pointer + temp_pointer ); + + n2 = tds_read_u_short_int ( filein ); + + for ( icor3 = 0; icor3 < n2; icor3++ ) { + cor3_tex_uv[0][icor3] = float_read ( filein ); + cor3_tex_uv[1][icor3] = float_read ( filein ); + } + + fseek ( filein, pointer, SEEK_SET ); + + return ( temp_pointer ); +} +/******************************************************************************/ + +unsigned long tds_read_texmap_section ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + TDS_READ_TEXMAP_SECTION tries to get the TEXMAP name from the TEXMAP section. + + Warning: + + The code has room for lots of textures. In this routine, we behave as + though there were only one, and we stick its name in the first name slot. + + Modified: + + 30 June 1999 + + Author: + + John Burkardt +*/ +{ + unsigned long int current_pointer; + long int pointer; + int teller; + unsigned long int temp_pointer; + + texture_num = texture_num + 1; + + current_pointer = ftell ( filein ) - 2; + temp_pointer = tds_read_u_long_int ( filein ); + + tds_read_u_short_int ( filein ); + tds_read_u_short_int ( filein ); + tds_read_u_short_int ( filein ); + tds_read_u_short_int ( filein ); + +/* + This next short int should equal A300. +*/ + tds_read_u_short_int ( filein ); + tds_read_u_long_int ( filein ); +/* + Now read the TEXMAP file name. +*/ + teller = tds_read_long_name ( filein ); + + if ( teller == -1 ) { + if ( debug ) { + printf ( " No TEXMAP name found.\n" ); + } + } + else { + strcpy ( texture_name[0], temp_name ); + if ( debug ) { + printf ( " TEXMAP name %s.\n", texture_name[0] ); + } + } + + pointer = ( long ) ( current_pointer + temp_pointer ); + fseek ( filein, pointer, SEEK_SET ); + + return ( temp_pointer ); +} +/******************************************************************************/ + +unsigned short int tds_read_u_short_int ( FILE *filein ) + +/******************************************************************************/ +{ + unsigned char c1; + unsigned char c2; + short int ival; + + c1 = fgetc ( filein ); + c2 = fgetc ( filein ); + + ival = c1 | ( c2 << 8 ); + + return ival; +} +/******************************************************************************/ + +unsigned long tds_read_spot_section ( FILE *filein ) + +/******************************************************************************/ +{ + unsigned long int current_pointer; + float falloff; + float hotspot; + long int pointer; + float target[4]; + unsigned long int temp_pointer; + + current_pointer = ftell ( filein ) - 2; + temp_pointer = tds_read_u_long_int ( filein ); + + target[0] = float_read ( filein ); + target[1] = float_read ( filein ); + target[2] = float_read ( filein ); + hotspot = float_read ( filein ); + falloff = float_read ( filein ); + + if ( debug ) { + printf ( " The target of the spot is XYZ = %f %f %f.\n", + target[0], target[1], target[2] ); + printf ( " The hotspot of this light is %f.\n", hotspot ); + printf ( " The falloff of this light is %f.\n", falloff ); + } + + pointer = ( long ) ( current_pointer + temp_pointer ); + + fseek ( filein, pointer, SEEK_SET ); + + return ( temp_pointer ); +} +/******************************************************************************/ + +unsigned long int tds_read_unknown_section ( FILE *filein ) + +/******************************************************************************/ +{ + unsigned long int current_pointer; + long int pointer; + unsigned long int temp_pointer; + + current_pointer = ftell ( filein ) - 2; + temp_pointer = tds_read_u_long_int ( filein ); + + pointer = ( long int ) ( current_pointer + temp_pointer ); + + fseek ( filein, pointer, SEEK_SET ); + + return ( temp_pointer ); +} +/******************************************************************************/ + +unsigned long tds_read_view_section ( FILE *filein, int *views_read ) + +/******************************************************************************/ +{ + unsigned long int current_pointer; + unsigned char end_found = FALSE; + long int pointer; + unsigned short int temp_int; + unsigned long int temp_pointer; + unsigned long int teller; + + current_pointer = ftell ( filein ) - 2; + temp_pointer = tds_read_u_long_int ( filein ); + teller = 6; + + while ( end_found == FALSE ) { + + temp_int = tds_read_u_short_int ( filein ); + teller = teller + 2; + + switch ( temp_int ) { + case 0x7012: + if ( debug ) { + printf ( " VIEWPORT_DATA_3 section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_vp_section ( filein, views_read ); + break; + case 0x7011: + if ( debug ) { + printf ( " VIEWPORT_DATA section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_unknown_section ( filein ); + break; + case 0x7020: + if ( debug ) { + printf ( " VIEWPORT_SIZE section tag of %0X\n", temp_int ); + } + teller = teller + tds_read_vp_section ( filein, views_read ); + break; + default: + break; + } + + if ( teller >= temp_pointer ) { + end_found = TRUE; + } + + if ( *views_read > 3 ) { + end_found = TRUE; + } + } + + pointer = ( long int ) ( current_pointer + temp_pointer ); + + fseek ( filein, pointer, SEEK_SET ); + + return ( temp_pointer ); +} +/******************************************************************************/ + +unsigned long tds_read_vp_section ( FILE *filein, int *views_read ) + +/******************************************************************************/ +{ + unsigned int attribs; + unsigned long int current_pointer; + int i; + int int_val; + long int pointer; + unsigned int port; + unsigned long int temp_pointer; + char *viewports[11] = { + "Bogus", + "Top", + "Bottom", + "Left", + "Right", + "Front", + "Back", + "User", + "Camera", + "Light", + "Disabled" + }; + + *views_read = *views_read + 1; + + current_pointer = ftell ( filein ) - 2; + temp_pointer = tds_read_u_long_int ( filein ); + + attribs = tds_read_u_short_int ( filein ); + + if ( attribs == 3 ) { + if ( debug ) { + printf ( " active in viewport.\n" ); + } + } + + if ( attribs == 5 ) { + if ( debug ) { + printf ( " active in viewport.\n" ); + } + } +/* + Read 5 INTS to get to the viewport information. +*/ + for ( i = 1; i < 6; i++ ) { + tds_read_u_short_int ( filein ); + } + + port = tds_read_u_short_int ( filein ); +/* + Find camera section. +*/ + if ( ( port == 0xffff ) || ( port == 0 ) ) { + + for ( i = 0; i < 12; i++ ) { + tds_read_u_short_int ( filein ); + } + + int_val = tds_read_name (filein ); + + if ( int_val == -1 ) { + if ( debug ) { + printf ( " No Camera name found\n" ); + } + } + + port = 0x0008; + } + + if ( debug ) { + printf ( "Reading [%s] information with tag:%d\n", viewports[port], port ); + } + + pointer = ( long int ) ( current_pointer + temp_pointer ); + + fseek ( filein, pointer, SEEK_SET ); + + return ( temp_pointer ); +} +/******************************************************************************/ + +int tds_write ( FILE *fileout ) + +/******************************************************************************/ + +/* + Purpose: + + TDS_WRITE writes graphics information to a 3D Studio Max 3DS file. + + Modified: + + 14 October 1998 + + Author: + + John Burkardt + +*/ +{ + float float_val; + int i; + int icor3; + int iface; + int j; + long int l0002; + long int l0100; + long int l3d3d; + long int l3d3e; + long int l4000; + long int l4100; + long int l4110; + long int l4120; + long int l4150; + long int l4160; + long int l4d4d; + long int lb000; + long int lb002; + long int lb00a; + long int lb008; + long int lb009; + long int lb010; + long int lb013; + long int lb020; + long int lb021; + long int lb022; + long int lb030; + long int long_int_val; + int name_length; + short int short_int_val; + unsigned short int u_short_int_val; + + bytes_num = 0; + name_length = strlen ( object_name ); + + l0002 = 10; + + l4150 = 2 + 4 + face_num * 4; + l4120 = 2 + 4 + 2 + 4 * face_num * 2 + l4150; + l4160 = 2 + 4 + 4 * 12; + l4110 = 2 + 4 + 2 + cor3_num * 3 * 4; + l4100 = 2 + 4 + l4110 + l4160 + l4120; + l4000 = 2 + 4 + ( name_length + 1 ) + l4100; + l0100 = 2 + 4 + 4; + l3d3e = 2 + 4 + 4; + l3d3d = 2 + 4 + l3d3e + l0100 + l4000; + + lb022 = 2 + 4 + 32; + lb021 = 2 + 4 + 9 * 4; + lb020 = 2 + 4 + 8 * 4; + lb013 = 2 + 4 + 6 * 2; + lb010 = 2 + 4 + ( name_length + 1 ) + 3 * 2; + lb030 = 2 + 4 + 2; + lb002 = 2 + 4 + lb030 + lb010 + lb013 + lb020 + lb021 + lb022; + lb009 = 2 + 4 + 4; + lb008 = 2 + 4 + 2 * 4; + lb00a = 2 + 4 + 2 + 9 + 2 * 2; + lb000 = 2 + 4 + lb00a + lb008 + lb009 + lb002; + + l4d4d = 2 + 4 + l0002 + l3d3d + lb000; +/* + M3DMAGIC begin. + tag, size. +*/ + short_int_val = ( short ) 0x4d4d; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, l4d4d ); +/* + M3D_VERSION begin. + tag, size, version. +*/ + short_int_val = ( short ) 0x0002; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, l0002 ); + long_int_val = 3; + bytes_num = bytes_num + long_int_write ( fileout, long_int_val ); +/* + M3D_VERSION end. + MDATA begin. + tag, size. +*/ + short_int_val = ( short ) 0x3d3d; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, l3d3d ); +/* + MESH_VERSION begin. + tag, size, version. +*/ + short_int_val = ( short ) 0x3d3e; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, l3d3e ); + long_int_val = 3; + bytes_num = bytes_num + long_int_write ( fileout, long_int_val ); +/* + MESH_VERSION end. + MASTER_SCALE begin. + tag, size, scale. +*/ + short_int_val = ( short ) 0x0100; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, l0100 ); + float_val = 1.0; + bytes_num = bytes_num + float_write ( fileout, float_val ); +/* + MASTER_SCALE end. + NAMED_OBJECT begin. + tag, size, name. +*/ + short_int_val = ( short ) 0x4000; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, l4000 ); + bytes_num = bytes_num + tds_write_string ( fileout, object_name ); +/* + N_TRI_OBJECT begin. + tag, size. +*/ + short_int_val = ( short ) 0x4100; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, l4100 ); +/* + POINT_ARRAY begin. + tag, size, number of points, coordinates of points. + Warning! number of points could exceed a short! +*/ + short_int_val = ( short ) 0x4110; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, l4110 ); + + u_short_int_val = ( unsigned short ) cor3_num; + bytes_num = bytes_num + tds_write_u_short_int ( fileout, u_short_int_val ); + + for ( icor3 = 0; icor3 < cor3_num; icor3++ ) { + for ( j = 0; j < 3; j++ ) { + bytes_num = bytes_num + float_write ( fileout, cor3[j][icor3] ); + } + } +/* + POINT_ARRAY end. + MESH_MATRIX begin. + tag, size, 4 by 3 matrix. +*/ + short_int_val = ( short ) 0x4160; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, l4160 ); + + for ( i = 0; i < 4; i++ ) { + for ( j = 0; j < 3; j++ ) { + float_val = transform_matrix[i][j]; + bytes_num = bytes_num + float_write ( fileout, float_val ); + } + } +/* + MESH_MATRIX end. + FACE_ARRAY begin. + tag, size, number of faces, nodes per face. + Warning: number of faces could exceed a short! +*/ + short_int_val = ( short ) 0x4120; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, l4120 ); + + u_short_int_val = ( unsigned short ) face_num; + bytes_num = bytes_num + tds_write_u_short_int ( fileout, u_short_int_val ); + + for ( iface = 0; iface < face_num; iface++ ) { + for ( j = 0; j < 3; j++ ) { + short_int_val = face[j][iface]; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + } + short_int_val = face_flags[iface]; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + } +/* + SMOOTH_GROUP begin. + tag, size, group for each face. +*/ + short_int_val = ( short ) 0x4150; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, l4150 ); + + for ( iface = 0; iface < face_num; iface++ ) { + long_int_val = face_smooth[iface]; + bytes_num = bytes_num + long_int_write ( fileout, long_int_val ); + } +/* + SMOOTH_GROUP end. + FACE_ARRAY end. + N_TRI_OBJECT end. + NAMED_OBJECT end. + MDATA end. + KFDATA begin. +*/ + short_int_val = ( short ) 0xb000; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, lb000 ); +/* + KFHDR begin. + tag, size, revision, filename, animlen. +*/ + short_int_val = ( short ) 0xb00a; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, lb00a ); + short_int_val = 5; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + tds_write_string ( fileout, "MAXSCENE" ); + short_int_val = 100; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); +/* + KFHDR end. + KFSEG begin. + tag, size, start, end. +*/ + short_int_val = ( short ) 0xb008; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, lb008 ); + long_int_val = 0; + bytes_num = bytes_num + long_int_write ( fileout, long_int_val ); + long_int_val = 100; + bytes_num = bytes_num + long_int_write ( fileout, long_int_val ); +/* + KFSEG end. + KFCURTIME begin. + tag, size, current_frame. +*/ + short_int_val = ( short ) 0xb009; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, lb009 ); + long_int_val = 0; + bytes_num = bytes_num + long_int_write ( fileout, long_int_val ); +/* + KFCURTIME end. + OBJECT_NODE_TAG begin. + tag, size. +*/ + short_int_val = ( short ) 0xb002; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, lb002 ); +/* + NODE_ID begin. + tag, size, id. +*/ + short_int_val = ( short ) 0xb030; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, lb030 ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); +/* + NODE_ID end. + NODE_HDR begin. + tag, size, object_name, flag1, flag2, hierarchy. +*/ + short_int_val = ( short ) 0xb010; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, lb010 ); + bytes_num = bytes_num + tds_write_string ( fileout, object_name ); + short_int_val = 16384; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = -1; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); +/* + NODE_HDR end. + PIVOT begin. + tag, size, pivot_x, pivot_y, pivot_z. +*/ + short_int_val = ( short ) 0xb013; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, lb013 ); + for ( i = 0; i < 3; i++ ) { + float_val = pivot[i]; + bytes_num = bytes_num + float_write ( fileout, float_val ); + } +/* + PIVOT end. + POS_TRACK_TAG begin. + tag, size, flag, i1, i2, i3, i4, i5, i6, frame, l1, pos_x, pos_y, pos_z. +*/ + short_int_val = ( short ) 0xb020; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, lb020 ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 1; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + long_int_val = 0; + bytes_num = bytes_num + long_int_write ( fileout, long_int_val ); + for ( i = 0; i < 3; i++ ) { + float_val = origin[i]; + bytes_num = bytes_num + float_write ( fileout, float_val ); + } +/* + POS_TRACK_TAG end. + ROT_TRACK_TAG begin. + tag, size, i1, i2, i3, i4, i5, i6, i7, i8, l1, rad, axis_x, axis_y, axis_z. +*/ + short_int_val = ( short ) 0xb021; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, lb021 ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 1; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + long_int_val = 0; + bytes_num = bytes_num + long_int_write ( fileout, long_int_val ); + float_val = 0.0; + bytes_num = bytes_num + float_write ( fileout, float_val ); + bytes_num = bytes_num + float_write ( fileout, float_val ); + bytes_num = bytes_num + float_write ( fileout, float_val ); + bytes_num = bytes_num + float_write ( fileout, float_val ); +/* + ROT_TRACK_TAG end. + SCL_TRACK_TAG begin. + tag, size, i1, i2, i3, i4, i5, i6, i7, i8, l1, scale_x, scale_y, scale_z. +*/ + short_int_val = ( short ) 0xb022; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + bytes_num = bytes_num + long_int_write ( fileout, lb022 ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 1; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + short_int_val = 0; + bytes_num = bytes_num + short_int_write ( fileout, short_int_val ); + long_int_val = 0; + bytes_num = bytes_num + long_int_write ( fileout, long_int_val ); + float_val = 1.0; + bytes_num = bytes_num + float_write ( fileout, float_val ); + bytes_num = bytes_num + float_write ( fileout, float_val ); + bytes_num = bytes_num + float_write ( fileout, float_val ); +/* + SCL_TRACK_TAG end. + OBJECT_NODE_TAG end. + KFDATA end. + M3DMAGIC end. +*/ + +/* + Report. +*/ + printf ( "TDS_WRITE wrote %d bytes.\n", bytes_num ); + + return SUCCESS; +} +/******************************************************************************/ + +int tds_write_string ( FILE *fileout, char *string ) + +/******************************************************************************/ + +/* + Modified: + + 23 September 1998 + + Author: + + John Burkardt +*/ +{ + char *c; + int nchar; + + nchar = 0; + + for ( c = string; nchar < 12; c++ ) { + + fputc ( *c, fileout ); + nchar = nchar + 1; + + if ( *c == 0 ) { + return nchar; + } + + } + + return nchar; +} +/******************************************************************************/ + +int tds_write_u_short_int ( FILE *fileout, unsigned short int short_int_val ) + +/******************************************************************************/ + +/* + Modified: + + 14 October 1998 + + Author: + + John Burkardt +*/ +{ + union { + unsigned short int yint; + char ychar[2]; + } y; + + y.yint = short_int_val; + + if ( byte_swap == TRUE ) { + fputc ( y.ychar[1], fileout ); + fputc ( y.ychar[0], fileout ); + } + else { + fputc ( y.ychar[0], fileout ); + fputc ( y.ychar[1], fileout ); + } + + return 2; +} +/**********************************************************************/ + +int tec_write ( FILE *fileout ) + +/**********************************************************************/ + +/* + Purpose: + + TEC_WRITE writes graphics information to a TECPLOT file. + + Discussion: + + The file format used is appropriate for 3D finite element surface + zone data. Polygons are decomposed into triangles where necessary. + + Example: + + TITLE = "cube.tec created by IVCON." + VARIABLES = "X", "Y", "Z", "R", "G", "B" + ZONE T="TRIANGLES", N=8, E=12, F=FEPOINT, ET=TRIANGLE + 0.0 0.0 0.0 0.0 0.0 0.0 + 1.0 0.0 0.0 1.0 0.0 0.0 + 1.0 1.0 0.0 1.0 1.0 0.0 + 0.0 1.0 0.0 0.0 1.0 0.0 + 0.0 0.0 1.0 0.0 0.0 1.0 + 1.0 0.0 1.0 1.0 0.0 1.0 + 1.0 1.0 1.0 1.0 1.0 1.0 + 0.0 1.0 1.0 0.0 1.0 1.0 + 1 4 2 + 2 4 3 + 1 5 8 + 1 2 5 + 2 6 5 + 2 3 6 + 3 7 6 + 3 4 7 + 4 8 7 + 4 1 8 + 5 6 8 + 6 7 8 + + Modified: + + 09 June 1999 + + Author: + + John Burkardt +*/ +{ + float b; + int face2[3]; + float g; + int icor3; + int iface; + int imat; + int j; + int face_num2; + int text_num; + float r; +/* + Determine the number of triangular faces. +*/ + face_num2 = 0; + for ( iface = 0; iface < face_num; iface++ ) { + for ( j = 0; j < face_order[iface] - 2; j++ ) { + face_num2 = face_num2 + 1; + } + } + + text_num = 0; + + fprintf ( fileout, "\"%s created by IVCON.\"\n", fileout_name ); + fprintf ( fileout, "VARIABLES = \"X\", \"Y\", \"Z\", \"R\", \"G\", \"B\"\n" ); + fprintf ( fileout, + "ZONE T=\"TRIANGLES\", N=%d, E=%d, F=FEPOINT, ET=TRIANGLE\n", + cor3_num, face_num2 ); + + text_num = text_num + 3; +/* + Write out X, Y, Z, R, G, B per node. +*/ + for ( icor3 = 0; icor3 < cor3_num; icor3++ ) { + imat = cor3_material[icor3]; + r = material_rgba[0][imat]; + g = material_rgba[1][imat]; + b = material_rgba[2][imat]; + fprintf ( fileout, "%f %f %f %f %f %f\n", cor3[0][icor3], cor3[1][icor3], + cor3[2][icor3], r, g, b ); + text_num = text_num + 1; + } +/* + Do the next face. +*/ + for ( iface = 0; iface < face_num; iface++ ) { +/* + Break the face up into triangles, anchored at node 1. +*/ + for ( j = 0; j < face_order[iface] - 2; j++ ) { + + face2[0] = face[ 0][iface] + 1; + face2[1] = face[j+1][iface] + 1; + face2[2] = face[j+2][iface] + 1; + + fprintf ( fileout, "%d %d %d\n", face2[0], face2[1], face2[2] ); + text_num = text_num + 1; + + } + + } +/* + Report. +*/ + printf ( "\n" ); + printf ( "TEC_WRITE - Wrote %d text lines.\n", text_num ); + + return SUCCESS; +} + +/*********************************************************************/ + +void tmat_init ( float a[4][4] ) + +/*********************************************************************/ + +/* + Purpose: + + TMAT_INIT initializes the geometric transformation matrix. + + Definition: + + The geometric transformation matrix can be thought of as a 4 by 4 + matrix "A" having components: + + r11 r12 r13 t1 + r21 r22 r23 t2 + r31 r32 r33 t3 + 0 0 0 1 + + This matrix encodes the rotations, scalings and translations that + are applied to graphical objects. + + A point P = (x,y,z) is rewritten in "homogeneous coordinates" as + PH = (x,y,z,1). Then to apply the transformations encoded in A to + the point P, we simply compute A * PH. + + Individual transformations, such as a scaling, can be represented + by simple versions of the transformation matrix. If the matrix + A represents the current set of transformations, and we wish to + apply a new transformation B, { the original points are + transformed twice: B * ( A * PH ). The new transformation B can + be combined with the original one A, to give a single matrix C that + encodes both transformations: C = B * A. + + Modified: + + 19 October 1998 + + Author: + + John Burkardt + + Reference: + + Foley, van Dam, Feiner, Hughes, + Computer Graphics, Principles and Practice, + Addison Wesley, Second Edition, 1990. + + Parameters: + + Input, float A[4][4], the geometric transformation matrix. +*/ +{ + int i; + int j; + + for ( i = 0; i < 4; i++ ) { + for ( j = 0; j < 4; j++ ) { + if ( i == j ) { + a[i][j] = 1.0; + } + else { + a[i][j] = 0.0; + } + } + } + return; +} +/*********************************************************************/ + +void tmat_mxm ( float a[4][4], float b[4][4], float c[4][4] ) + +/*********************************************************************/ + +/* + Purpose: + + TMAT_MXM multiplies two geometric transformation matrices. + + Note: + + The product is accumulated in a temporary array, and { assigned + to the result. Therefore, it is legal for any two, or all three, + of the arguments to share memory. + + Modified: + + 19 October 1998 + + Author: + + John Burkardt + + Reference: + + Foley, van Dam, Feiner, Hughes, + Computer Graphics, Principles and Practice, + Addison Wesley, Second Edition, 1990. + + Parameters: + + Input, float A[4][4], the first geometric transformation matrix. + + Input, float B[4][4], the second geometric transformation matrix. + + Output, float C[4][4], the product A * B. +*/ +{ + float d[4][4]; + int i; + int j; + int k; + + for ( i = 0; i < 4; i++ ) { + for ( k = 0; k < 4; k++ ) { + d[i][k] = 0.0; + for ( j = 0; j < 4; j++ ) { + d[i][k] = d[i][k] + a[i][j] * b[j][k]; + } + } + } + + for ( i = 0; i < 4; i++ ) { + for ( j = 0; j < 4; j++ ) { + c[i][j] = d[i][j]; + } + } + return; +} +/*********************************************************************/ + +void tmat_mxp ( float a[4][4], float x[4], float y[4] ) + +/*********************************************************************/ + +/* + Purpose: + + TMAT_MXP multiplies a geometric transformation matrix times a point. + + Modified: + + 19 October 1998 + + Author: + + John Burkardt + + Reference: + + Foley, van Dam, Feiner, Hughes, + Computer Graphics, Principles and Practice, + Addison Wesley, Second Edition, 1990. + + Parameters: + + Input, float A[4][4], the geometric transformation matrix. + + Input, float X[4], the point to be multiplied. The fourth component + of X is implicitly assigned the value of 1. + + Output, float Y[4], the result of A*X. The product is accumulated in + a temporary vector, and { assigned to the result. Therefore, it + is legal for X and Y to share memory. +*/ +{ + int i; + int j; + float z[4]; + + for ( i = 0; i < 3; i++ ) { + z[i] = a[i][3]; + for ( j = 0; j < 3; j++ ) { + z[i] = z[i] + a[i][j] * x[j]; + } + } + + for ( i = 0; i < 3; i++ ) { + y[i] = z[i]; + } + return; +} +/*********************************************************************/ + +void tmat_mxp2 ( float a[4][4], float x[][3], float y[][3], int n ) + +/*********************************************************************/ + +/* + Purpose: + + TMAT_MXP2 multiplies a geometric transformation matrix times N points. + + Modified: + + 20 October 1998 + + Author: + + John Burkardt + + Reference: + + Foley, van Dam, Feiner, Hughes, + Computer Graphics, Principles and Practice, + Addison Wesley, Second Edition, 1990. + + Parameters: + + Input, float A[4][4], the geometric transformation matrix. + + Input, float X[N][3], the points to be multiplied. + + Output, float Y[N][3], the transformed points. Each product is + accumulated in a temporary vector, and { assigned to the + result. Therefore, it is legal for X and Y to share memory. + +*/ +{ + int i; + int j; + int k; + float z[4]; + + for ( k = 0; k < n; k++ ) { + + for ( i = 0; i < 3; i++ ) { + z[i] = a[i][3]; + for ( j = 0; j < 3; j++ ) { + z[i] = z[i] + a[i][j] * x[k][j]; + } + } + + for ( i = 0; i < 3; i++ ) { + y[k][i] = z[i]; + } + + } + return; +} +/*********************************************************************/ + +void tmat_mxv ( float a[4][4], float x[4], float y[4] ) + +/*********************************************************************/ + +/* + Purpose: + + TMAT_MXV multiplies a geometric transformation matrix times a vector. + + Modified: + + 12 August 1999 + + Author: + + John Burkardt + + Reference: + + Foley, van Dam, Feiner, Hughes, + Computer Graphics, Principles and Practice, + Addison Wesley, Second Edition, 1990. + + Parameters: + + Input, float A[4][4], the geometric transformation matrix. + + Input, float X[3], the vector to be multiplied. The fourth component + of X is implicitly assigned the value of 1. + + Output, float Y[3], the result of A*X. The product is accumulated in + a temporary vector, and assigned to the result. Therefore, it + is legal for X and Y to share memory. +*/ +{ + int i; + int j; + float z[4]; + + for ( i = 0; i < 3; i++ ) { + z[i] = 0.0; + for ( j = 0; j < 3; j++ ) { + z[i] = z[i] + a[i][j] * x[j]; + } + z[i] = z[i] + a[i][3]; + } + + for ( i = 0; i < 3; i++ ) { + y[i] = z[i]; + } + return; +} +/*********************************************************************/ + +void tmat_rot_axis ( float a[4][4], float b[4][4], float angle, + char axis ) + +/*********************************************************************/ + +/* + Purpose: + + TMAT_ROT_AXIS applies an axis rotation to the geometric transformation matrix. + + Modified: + + 19 April 1999 + + Author: + + John Burkardt + + Reference: + + Foley, van Dam, Feiner, Hughes, + Computer Graphics, Principles and Practice, + Addison Wesley, Second Edition, 1990. + + Parameters: + + Input, float A[4][4], the current geometric transformation matrix. + + Output, float B[4][4], the modified geometric transformation matrix. + A and B may share the same memory. + + Input, float ANGLE, the angle, in degrees, of the rotation. + + Input, character AXIS, is 'X', 'Y' or 'Z', specifying the coordinate + axis about which the rotation occurs. +*/ +{ + float c[4][4]; + float d[4][4]; + int i; + int j; + float theta; + + theta = angle * DEG_TO_RAD; + + tmat_init ( c ); + + if ( axis == 'X' || axis == 'x' ) { + c[1][1] = cos ( theta ); + c[1][2] = - sin ( theta ); + c[2][1] = sin ( theta ); + c[2][2] = cos ( theta ); + } + else if ( axis == 'Y' || axis == 'y' ) { + c[0][0] = cos ( theta ); + c[0][2] = sin ( theta ); + c[2][0] = - sin ( theta ); + c[2][2] = cos ( theta ); + } + else if ( axis == 'Z' || axis == 'z' ) { + c[0][0] = cos ( theta ); + c[0][1] = - sin ( theta ); + c[1][0] = sin ( theta ); + c[1][1] = cos ( theta ); + } + else { + printf ( "\n" ); + printf ( "TMAT_ROT_AXIS - Fatal error!\n" ); + printf ( " Illegal rotation axis: %c.\n", axis ); + printf ( " Legal choices are 'X', 'Y', or 'Z'.\n" ); + return; + } + + tmat_mxm ( c, a, d ); + + for ( i = 0; i < 4; i++ ) { + for ( j = 0; j < 4; j++ ) { + b[i][j] = d[i][j]; + } + } + return; +} +/*********************************************************************/ + +void tmat_rot_vector ( float a[4][4], float b[4][4], float angle, + float v1, float v2, float v3 ) + +/*********************************************************************/ + +/* + Purpose: + + TMAT_ROT_VECTOR applies a rotation about a vector to the geometric transformation matrix. + + Modified: + + 27 July 1999 + + Author: + + John Burkardt + + Reference: + + Foley, van Dam, Feiner, Hughes, + Computer Graphics, Principles and Practice, + Addison Wesley, Second Edition, 1990. + + Parameters: + + Input, float A[4][4], the current geometric transformation matrix. + + Output, float B[4][4], the modified geometric transformation matrix. + A and B may share the same memory. + + Input, float ANGLE, the angle, in degrees, of the rotation. + + Input, float V1, V2, V3, the X, Y and Z coordinates of a (nonzero) + point defining a vector from the origin. The rotation will occur + about this axis. +*/ +{ + float c[4][4]; + float ca; + float d[4][4]; + int i; + int j; + float sa; + float theta; + + if ( v1 * v1 + v2 * v2 + v3 * v3 == 0.0 ) { + return; + } + + theta = angle * DEG_TO_RAD; + + tmat_init ( c ); + + ca = cos ( theta ); + sa = sin ( theta ); + + c[0][0] = v1 * v1 + ca * ( 1.0 - v1 * v1 ); + c[0][1] = ( 1.0 - ca ) * v1 * v2 - sa * v3; + c[0][2] = ( 1.0 - ca ) * v1 * v3 + sa * v2; + + c[1][0] = ( 1.0 - ca ) * v2 * v1 + sa * v3; + c[1][1] = v2 * v2 + ca * ( 1.0 - v2 * v2 ); + c[1][2] = ( 1.0 - ca ) * v2 * v3 - sa * v1; + + c[2][0] = ( 1.0 - ca ) * v3 * v1 - sa * v2; + c[2][1] = ( 1.0 - ca ) * v3 * v2 + sa * v1; + c[2][2] = v3 * v3 + ca * ( 1.0 - v3 * v3 ); + + tmat_mxm ( c, a, d ); + + for ( i = 0; i < 4; i++ ) { + for ( j = 0; j < 4; j++ ) { + b[i][j] = d[i][j]; + } + } + return; +} +/*********************************************************************/ + +void tmat_scale ( float a[4][4], float b[4][4], float sx, float sy, + float sz ) + +/*********************************************************************/ + +/* + Purpose: + + TMAT_SCALE applies a scaling to the geometric transformation matrix. + + Modified: + + 19 October 1998 + + Author: + + John Burkardt + + Reference: + + Foley, van Dam, Feiner, Hughes, + Computer Graphics, Principles and Practice, + Addison Wesley, Second Edition, 1990. + + Parameters: + + Input, float A[4][4], the current geometric transformation matrix. + + Output, float B[4][4], the modified geometric transformation matrix. + A and B may share the same memory. + + Input, float SX, SY, SZ, the scalings to be applied to the X, Y and + Z coordinates. +*/ +{ + float c[4][4]; + float d[4][4]; + int i; + int j; + + tmat_init ( c ); + + c[0][0] = sx; + c[1][1] = sy; + c[2][2] = sz; + + tmat_mxm ( c, a, d ); + + for ( i = 0; i < 4; i++ ) { + for ( j = 0; j < 4; j++ ) { + b[i][j] = d[i][j]; + } + } + return; +} +/*********************************************************************/ + +void tmat_shear ( float a[4][4], float b[4][4], char *axis, float s ) + +/*********************************************************************/ + +/* + Purpose: + + TMAT_SHEAR applies a shear to the geometric transformation matrix. + + Modified: + + 19 October 1998 + + Author: + + John Burkardt + + Reference: + + Foley, van Dam, Feiner, Hughes, + Computer Graphics, Principles and Practice, + Addison Wesley, Second Edition, 1990. + + Parameters: + + Input, float A[4][4], the current geometric transformation matrix. + + Output, float B[4][4], the modified geometric transformation matrix. + A and B may share the same memory. + + Input, character*3 AXIS, is 'XY', 'XZ', 'YX', 'YZ', 'ZX' or 'ZY', + specifying the shear equation: + + XY: x' = x + s * y; + XZ: x' = x + s * z; + YX: y' = y + s * x; + YZ: y' = y + s * z; + ZX: z' = z + s * x; + ZY: z' = z + s * y. + + Input, float S, the shear coefficient. +*/ +{ + float c[4][4]; + float d[4][4]; + int i; + int j; + + tmat_init ( c ); + + if ( strcmp ( axis, "XY" ) == 0 || strcmp ( axis, "xy" ) == 0 ) { + c[0][1] = s; + } + else if ( strcmp ( axis, "XZ" ) == 0 || strcmp ( axis, "xz" ) == 0 ) { + c[0][2] = s; + } + else if ( strcmp ( axis, "YX" ) == 0 || strcmp ( axis, "yx" ) == 0 ) { + c[1][0] = s; + } + else if ( strcmp ( axis, "YZ" ) == 0 || strcmp ( axis, "yz" ) == 0 ) { + c[1][2] = s; + } + else if ( strcmp ( axis, "ZX" ) == 0 || strcmp ( axis, "zx" ) == 0 ) { + c[2][0] = s; + } + else if ( strcmp ( axis, "ZY" ) == 0 || strcmp ( axis, "zy" ) == 0 ) { + c[2][1] = s; + } + else { + printf ( "\n" ); + printf ( "TMAT_SHEAR - Fatal error!\n" ); + printf ( " Illegal shear axis: %s.\n", axis ); + printf ( " Legal choices are XY, XZ, YX, YZ, ZX, or ZY.\n" ); + return; + } + + tmat_mxm ( c, a, d ); + + for ( i = 0; i < 4; i++ ) { + for ( j = 0; j < 4; j++ ) { + b[i][j] = d[i][j]; + } + } + return; +} +/*********************************************************************/ + +void tmat_trans ( float a[4][4], float b[4][4], float x, float y, + float z ) + +/*********************************************************************/ + +/* + Purpose: + + TMAT_TRANS applies a translation to the geometric transformation matrix. + + Modified: + + 19 October 1998 + + Author: + + John Burkardt + + Reference: + + Foley, van Dam, Feiner, Hughes, + Computer Graphics, Principles and Practice, + Addison Wesley, Second Edition, 1990. + + Parameters: + + Input, float A[4][4], the current geometric transformation matrix. + + Output, float B[4][4], the modified transformation matrix. + A and B may share the same memory. + + Input, float X, Y, Z, the translation. This may be thought of as the + point that the origin moves to under the translation. +*/ +{ + int i; + int j; + + for ( i = 0; i < 4; i++ ) { + for ( j = 0; j < 4; j++ ) { + b[i][j] = a[i][j]; + } + } + b[0][3] = b[0][3] + x; + b[1][3] = b[1][3] + y; + b[2][3] = b[2][3] + z; + + return; +} +/******************************************************************************/ + +int tria_read ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + TRIA_READ reads an ASCII triangle file. + + Example: + + 12 <-- Number of triangles + + (x,y,z) and (nx,ny,nz) of normal vector at: + + 0.0 0.0 0.0 0.3 0.3 0.3 node 1 of triangle 1. + 1.0 0.0 0.0 0.3 0.1 0.3 node 2 of triangle 1, + 0.0 1.0 0.0 0.3 0.1 0.3 node 3 of triangle 1, + 1.0 0.5 0.0 0.3 0.1 0.3 node 1 of triangle 2, + ... + 0.0 0.5 0.5 0.3 0.1 0.3 node 3 of triangle 12. + + Modified: + + 22 June 1999 + + Author: + + John Burkardt +*/ +{ + float cvec[3]; + int icor3; + int iface; + int iface_hi; + int iface_lo; + int ivert; + int face_num2; + float r1; + float r2; + float r3; + float r4; + float r5; + float r6; +/* + Get the number of triangles. +*/ + fgets ( input, LINE_MAX_LEN, filein ); + text_num = text_num + 1; + sscanf ( input, "%d", &face_num2 ); +/* + For each triangle: +*/ + iface_lo = face_num; + iface_hi = face_num + face_num2; + + for ( iface = iface_lo; iface < iface_hi; iface++ ) { + + if ( iface < FACE_MAX ) { + face_order[iface] = 3; + face_material[iface] = 0; + } +/* + For each face: +*/ + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + + fgets ( input, LINE_MAX_LEN, filein ); + text_num = text_num + 1; + sscanf ( input, "%e %e %e %e %e %e", &r1, &r2, &r3, &r4, &r5, &r6 ); + + cvec[0] = r1; + cvec[1] = r2; + cvec[2] = r3; + + if ( cor3_num < 1000 ) { + icor3 = rcol_find ( cor3, 3, cor3_num, cvec ); + } + else { + icor3 = -1; + } + + if ( icor3 == -1 ) { + icor3 = cor3_num; + if ( cor3_num < COR3_MAX ) { + cor3[0][cor3_num] = cvec[0]; + cor3[1][cor3_num] = cvec[1]; + cor3[2][cor3_num] = cvec[2]; + } + cor3_num = cor3_num + 1; + } + else { + dup_num = dup_num + 1; + } + + if ( iface < FACE_MAX ) { + + face[ivert][iface] = icor3; + vertex_material[ivert][iface] = 0; + vertex_normal[0][ivert][iface] = r4; + vertex_normal[1][ivert][iface] = r5; + vertex_normal[2][ivert][iface] = r6; + } + + } + } + face_num = face_num + face_num2; + + return SUCCESS; +} +/**********************************************************************/ + +int tria_write ( FILE *fileout ) + +/**********************************************************************/ + +/* + Purpose: + + TRIA_WRITE writes the graphics data to an ASCII "triangle" file. + + Discussion: + + This is just a private format that Greg Hood requested from me. + + Example: + + 12 <-- Number of triangles + + (x,y,z) and (nx,ny,nz) of normal vector at: + + 0.0 0.0 0.0 0.3 0.3 0.3 node 1 of triangle 1. + 1.0 0.0 0.0 0.3 0.1 0.3 node 2 of triangle 1, + 0.0 1.0 0.0 0.3 0.1 0.3 node 3 of triangle 1, + 1.0 0.5 0.0 0.3 0.1 0.3 node 1 of triangle 2, + ... + 0.0 0.5 0.5 0.3 0.1 0.3 node 3 of triangle 12. + + Modified: + + 10 June 1999 + + Author: + + John Burkardt +*/ +{ + int face2[3]; + int icor3; + int iface; + int jlo; + int k; + int face_num2; + int text_num; + float nx; + float ny; + float nz; + float x; + float y; + float z; + + text_num = 0; +/* + Determine the number of triangular faces. +*/ + face_num2 = 0; + for ( iface = 0; iface < face_num; iface++ ) { + for ( jlo = 0; jlo < face_order[iface] - 2; jlo ++ ) { + face_num2 = face_num2 + 1; + } + } + + fprintf ( fileout, "%d\n", face_num2 ); + text_num = text_num + 1; +/* + Do the next face. +*/ + for ( iface = 0; iface < face_num; iface++ ) { +/* + Break the face up into triangles, anchored at node 1. +*/ + for ( jlo = 0; jlo < face_order[iface] - 2; jlo ++ ) { + + face2[0] = face[ 0][iface]; + face2[1] = face[jlo+1][iface]; + face2[2] = face[jlo+2][iface]; + + for ( k = 0; k < 3; k++ ) { + + icor3 = face2[k]; + + x = cor3[0][icor3]; + y = cor3[1][icor3]; + z = cor3[2][icor3]; + + nx = cor3_normal[0][icor3]; + ny = cor3_normal[1][icor3]; + nz = cor3_normal[2][icor3]; + + fprintf ( fileout, "%f %f %f %f %f %f\n", x, y, z, nx, ny, nz ); + + text_num = text_num + 1; + + } + + } + + } +/* + Report. +*/ + printf ( "\n" ); + printf ( "TRIA_WRITE - Wrote %d text lines.\n", text_num ); + + return SUCCESS; +} +/******************************************************************************/ + +int trib_read ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + TRIB_READ reads a binary triangle file. + + Example: + + 4 byte int = number of triangles + + For each triangular face: + + 3 4-byte floats = coordinates of first node; + 3 4-byte floats = components of normal vector at first node; + 3 4-byte floats = coordinates of second node; + 3 4-byte floats = components of normal vector at second node; + 3 4-byte floats = coordinates of third node; + 3 4-byte floats = components of normal vector at third node. + + Modified: + + 22 June 1999 + + Author: + + John Burkardt +*/ +{ + float cvec[3]; + int icor3; + int i; + int iface; + int iface_hi; + int iface_lo; + int ivert; + int face_num2; +/* + Read the number of triangles in the file. +*/ + face_num2 = long_int_read ( filein ); + bytes_num = bytes_num + 4; +/* + For each (triangular) face, + read the coordinates and normal vectors of three vertices, +*/ + iface_lo = face_num; + iface_hi = face_num + face_num2; + + for ( iface = iface_lo; iface < iface_hi; iface++ ) { + + if ( iface < FACE_MAX ) { + face_order[iface] = 3; + face_material[iface] = 0; + } + + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + + for ( i = 0; i < 3; i++ ) { + cvec[i] = float_read ( filein ); + bytes_num = bytes_num + 4; + } + + if ( cor3_num < 1000 ) { + icor3 = rcol_find ( cor3, 3, cor3_num, cvec ); + } + else { + icor3 = -1; + } + + if ( icor3 == -1 ) { + icor3 = cor3_num; + if ( cor3_num < COR3_MAX ) { + cor3[0][cor3_num] = cvec[0]; + cor3[1][cor3_num] = cvec[1]; + cor3[2][cor3_num] = cvec[2]; + } + cor3_num = cor3_num + 1; + } + else { + dup_num = dup_num + 1; + } + + if ( iface < FACE_MAX ) { + + face[ivert][iface] = icor3; + vertex_material[ivert][iface] = 0; + + for ( i = 0; i < 3; i++ ) { + vertex_normal[i][ivert][iface] = float_read ( filein ); + bytes_num = bytes_num + 4; + } + + } + + } + } + + face_num = face_num + face_num2; + + return SUCCESS; +} +/**********************************************************************/ + +int trib_write ( FILE *fileout ) + +/**********************************************************************/ + +/* + Purpose: + + TRIB_WRITE writes the graphics data to a binary "triangle" file. + + Discussion: + + This is just a private format that Greg Hood requested from me. + + Example: + + 12 Number of triangles + 0.0 x at node 1, triangle 1, + 0.0 y at node 1, triangle 1, + 0.0 z at node 1, triangle 1, + 0.3 nx at node 1, triangle 1, + 0.3 ny at node 1, triangle 1, + 0.3 nz at node 1, triangle 1. + 1.0 x at node 2, triangle 1, + ... + 0.7 nz at node 3, triangle 1. + 1.2 x at node 1, triangle 2, + ... + 0.3 nz at node 3, triangle 2. + 9.3 x at node 1, triangle 3, + ... + 0.3 nz at node 3, triangle 12. + + Modified: + + 16 June 1999 + + Author: + + John Burkardt +*/ +{ + int face2[3]; + int icor3; + int iface; + int jlo; + int k; + int face_num2; + float nx; + float ny; + float nz; + float x; + float y; + float z; + + bytes_num = 0; +/* + Determine the number of triangular faces. +*/ + face_num2 = 0; + for ( iface = 0; iface < face_num; iface++ ) { + for ( jlo = 0; jlo < face_order[iface] - 2; jlo ++ ) { + face_num2 = face_num2 + 1; + } + } + + bytes_num = bytes_num + long_int_write ( fileout, face_num2 ); +/* + Do the next face. +*/ + for ( iface = 0; iface < face_num; iface++ ) { +/* + Break the face up into triangles, anchored at node 1. +*/ + for ( jlo = 0; jlo < face_order[iface] - 2; jlo ++ ) { + + face2[0] = face[ 0][iface]; + face2[1] = face[jlo+1][iface]; + face2[2] = face[jlo+2][iface]; + + for ( k = 0; k < 3; k++ ) { + + icor3 = face2[k]; + + x = cor3[0][icor3]; + y = cor3[1][icor3]; + z = cor3[2][icor3]; + + nx = cor3_normal[0][icor3]; + ny = cor3_normal[1][icor3]; + nz = cor3_normal[2][icor3]; + + bytes_num = bytes_num + float_write ( fileout, x ); + bytes_num = bytes_num + float_write ( fileout, y ); + bytes_num = bytes_num + float_write ( fileout, z ); + bytes_num = bytes_num + float_write ( fileout, nx ); + bytes_num = bytes_num + float_write ( fileout, ny ); + bytes_num = bytes_num + float_write ( fileout, nz ); + + } + + } + + } +/* + Report. +*/ + printf ( "\n" ); + printf ( "TRIB_WRITE - Wrote %d bytes.\n", bytes_num ); + + return SUCCESS; +} +/******************************************************************************/ + +int txt_write ( FILE *fileout ) + +/******************************************************************************/ + +/* + Purpose: + + TXT_WRITE writes the graphics data to a text file. + + Modified: + + 25 June 1998 + + Author: + + John Burkardt +*/ +{ + int i; + int iface; + int iline; + int imat; + int ivert; + int nitem; + int text_num; + + text_num = 0; + + fprintf ( fileout, "%s created by IVCON.\n", fileout_name ); + fprintf ( fileout, "Original data in %s.\n", filein_name ); + fprintf ( fileout, "Object name is %s.\n", object_name ); + fprintf ( fileout, "Object origin at %f %f %f.\n", origin[0], origin[1], + origin[2] ); + fprintf ( fileout, "Object pivot at %f %f %f.\n", pivot[0], pivot[1], + pivot[2] ); + text_num = text_num + 5; +/* + TRANSFORMATION MATRIX. +*/ + fprintf ( fileout, "\n" ); + fprintf ( fileout, "Transformation matrix:\n" ); + fprintf ( fileout, "\n" ); + text_num = text_num + 3; + + for ( i = 0; i < 4; i++ ) { + fprintf ( fileout, " %f %f %f %f\n", transform_matrix[i][0], + transform_matrix[i][1], transform_matrix[i][2], transform_matrix[i][3] ); + text_num = text_num + 1; + } +/* + NODES. +*/ + fprintf ( fileout, "\n" ); + fprintf ( fileout, " %d nodes.\n", cor3_num ); + text_num = text_num + 2; + + if ( cor3_num > 0 ) { + + fprintf ( fileout, "\n" ); + fprintf ( fileout, " Node coordinate data:\n" ); + fprintf ( fileout, "\n" ); + text_num = text_num + 3; + + for ( i = 0; i < cor3_num; i++ ) { + fprintf ( fileout, " %d %f %f %f\n ", i, cor3[0][i], cor3[1][i], + cor3[2][i] ); + text_num = text_num + 1; + } + + fprintf ( fileout, "\n" ); + fprintf ( fileout, " Node normal vectors:\n" ); + fprintf ( fileout, "\n" ); + text_num = text_num + 3; + + for ( i = 0; i < cor3_num; i++ ) { + fprintf ( fileout, " %d %f %f %f\n ", i, cor3_normal[0][i], + cor3_normal[1][i], cor3_normal[2][i] ); + text_num = text_num + 1; + } + + fprintf ( fileout, "\n" ); + fprintf ( fileout, " Node materials:\n" ); + fprintf ( fileout, "\n" ); + text_num = text_num + 3; + + for ( i = 0; i < cor3_num; i++ ) { + fprintf ( fileout, " %d %d\n ", i, cor3_material[i] ); + text_num = text_num + 1; + } + + if ( texture_num > 0 ) { + fprintf ( fileout, "\n" ); + fprintf ( fileout, " Node texture coordinates:\n" ); + fprintf ( fileout, "\n" ); + text_num = text_num + 3; + + for ( i = 0; i < cor3_num; i++ ) { + fprintf ( fileout, " %d %f %f\n ", i, cor3_tex_uv[0][i], + cor3_tex_uv[1][i] ); + text_num = text_num + 1; + } + } + } +/* + LINES. +*/ + fprintf ( fileout, "\n" ); + fprintf ( fileout, " %d line data items.\n", line_num ); + text_num = text_num + 2; + + if ( line_num > 0 ) { + + fprintf ( fileout, "\n" ); + fprintf ( fileout, " Line index data:\n" ); + fprintf ( fileout, "\n" ); + text_num = text_num + 3; + + nitem = 0; + + for ( iline = 0; iline < line_num; iline++ ) { + + fprintf ( fileout, " %d", line_dex[iline] ); + nitem = nitem + 1; + + if ( iline == line_num - 1 || line_dex[iline] == -1 || nitem >= 10 ) { + nitem = 0; + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + } + + } + + fprintf ( fileout, "\n" ); + fprintf ( fileout, " Line materials:\n" ); + fprintf ( fileout, "\n" ); + text_num = text_num + 3; + + nitem = 0; + + for ( iline = 0; iline < line_num; iline++ ) { + + fprintf ( fileout, " %d", line_material[iline] ); + nitem = nitem + 1; + + if ( iline == line_num - 1 || line_material[iline] == -1 || nitem >= 10 ) { + nitem = 0; + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + } + } + + } +/* + COLOR DATA +*/ + fprintf ( fileout, "\n" ); + fprintf ( fileout, " %d colors.\n", color_num ); + text_num = text_num + 2; +/* + FACES. +*/ + fprintf ( fileout, "\n" ); + fprintf ( fileout, " %d faces.\n", face_num ); + text_num = text_num + 2; + + if ( face_num > 0 ) { + + fprintf ( fileout, "\n" ); + fprintf ( fileout, " Face, Material, Number of vertices, Smoothing, Flags:\n" ); + fprintf ( fileout, "\n" ); + text_num = text_num + 3; + + for ( iface = 0; iface < face_num; iface++ ) { + fprintf ( fileout, " %d %d %d %d %d\n", iface, face_material[iface], + face_order[iface], face_smooth[iface], face_flags[iface] ); + text_num = text_num + 1; + } + + fprintf ( fileout, "\n" ); + fprintf ( fileout, " Face, Vertices\n" ); + fprintf ( fileout, "\n" ); + text_num = text_num + 3; + + for ( iface = 0; iface < face_num; iface++ ) { + + fprintf ( fileout, "%d ", iface ); + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + fprintf ( fileout, " %d", face[ivert][iface] ); + } + + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + } + + fprintf ( fileout, "\n" ); + fprintf ( fileout, " Face normal vectors:\n" ); + fprintf ( fileout, "\n" ); + text_num = text_num + 3; + + for ( iface = 0; iface < face_num; iface++ ) { + fprintf ( fileout, " %d %f %f %f\n", iface, face_normal[0][iface], + face_normal[1][iface], face_normal[2][iface] ); + text_num = text_num + 1; + } + + if ( texture_num > 0 ) { + + fprintf ( fileout, "\n" ); + fprintf ( fileout, " Face texture coordinates:\n" ); + fprintf ( fileout, "\n" ); + text_num = text_num + 3; + + for ( iface = 0; iface < face_num; iface++ ) { + fprintf ( fileout, " %d %f %f\n", iface, face_tex_uv[0][iface], + face_tex_uv[1][iface] ); + text_num = text_num + 1; + } + } + } +/* + VERTICES. +*/ + if ( face_num > 0 ) { + + fprintf ( fileout, "\n" ); + fprintf ( fileout, "Vertex normal vectors:\n" ); + text_num = text_num + 2; + + for ( iface = 0; iface < face_num; iface++ ) { + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + fprintf ( fileout, " %d %d %f %f %f\n", iface, ivert, + vertex_normal[0][ivert][iface], vertex_normal[1][ivert][iface], + vertex_normal[2][ivert][iface] ); + text_num = text_num + 1; + } + } + + fprintf ( fileout, "\n" ); + fprintf ( fileout, "Vertex materials:\n" ); + fprintf ( fileout, "\n" ); + text_num = text_num + 3; + + for ( iface = 0; iface < face_num; iface++ ) { + fprintf ( fileout, "%d", iface ); + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + fprintf ( fileout, " %d", vertex_material[ivert][iface] ); + } + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + } + + if ( texture_num > 0 ) { + + fprintf ( fileout, "\n" ); + fprintf ( fileout, "Vertex UV texture coordinates:\n" ); + fprintf ( fileout, "\n" ); + text_num = text_num + 3; + + for ( iface = 0; iface < face_num; iface++ ) { + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + fprintf ( fileout, "%d %d %f %f\n", iface, ivert, + vertex_tex_uv[0][ivert][iface], vertex_tex_uv[1][ivert][iface] ); + text_num = text_num + 1; + } + } + } + } +/* + MATERIALS. +*/ + fprintf ( fileout, "\n" ); + fprintf ( fileout, "%d materials.\n", material_num ); + fprintf ( fileout, "\n" ); + fprintf ( fileout, "Index Name R G B A\n" ); + fprintf ( fileout, "\n" ); + + text_num = text_num + 5; + + for ( imat = 0; imat < material_num; imat++ ) { + fprintf ( fileout, "%d %s %f %f %f %f\n", imat, material_name[imat], + material_rgba[0][imat], material_rgba[1][imat], material_rgba[2][imat], + material_rgba[3][imat] ); + text_num = text_num + 1; + } +/* + TEXTURES. +*/ + fprintf ( fileout, "\n" ); + fprintf ( fileout, "%d textures.\n", texture_num ); + text_num = text_num + 2; + + if ( texture_num > 0 ) { + fprintf ( fileout, "\n" ); + fprintf ( fileout, "Index Name\n" ); + fprintf ( fileout, "\n" ); + for ( i = 0; i < texture_num; i++ ) { + fprintf ( fileout, "%d %s\n", i, texture_name[i] ); + } + text_num = text_num + 3; + } +/* + Report. +*/ + printf ( "\n" ); + printf ( "TXT_WRITE - Wrote %d text lines.\n", text_num ); + + return SUCCESS; +} +/**********************************************************************/ + +int ucd_write ( FILE *fileout ) + +/**********************************************************************/ + +/* + Purpose: + + UCD_WRITE writes graphics data to an AVS UCD file. + + Examples: + + # cube.ucd created by IVREAD. + # + # Material RGB to hue map: + # + # material R G B Alpha Hue + # + # 0 0.94 0.70 0.15 1.000 0.116 + # 1 0.24 0.70 0.85 1.000 0.541 + # 2 0.24 0.00 0.85 1.000 0.666 + # + # The node data is + # node # / material # / RGBA / Hue + # + 8 6 6 0 0 + 0 0.0 0.0 0.0 + 1 1.0 0.0 0.0 + 2 1.0 1.0 0.0 + 3 0.0 1.0 0.0 + 4 0.0 0.0 1.0 + 5 1.0 0.0 1.0 + 6 1.0 1.0 1.0 + 7 0.0 1.0 1.0 + 0 0 quad 0 1 2 3 + 1 0 quad 0 4 5 1 + 2 0 quad 1 5 6 2 + 3 0 quad 2 6 7 3 + 4 0 quad 3 7 4 0 + 5 0 quad 4 7 6 5 + 3 1 4 1 + material, 0...2 + RGBA, 0-1/0-1/0-1/0-1 + Hue, 0-1 + 0 0 0.94 0.70 0.15 1.0 0.116 + 1 0 0.94 0.70 0.15 1.0 0.116 + 2 0 0.94 0.70 0.15 1.0 0.116 + 3 0 0.94 0.70 0.15 1.0 0.116 + 4 1 0.24 0.70 0.85 1.0 0.541 + 5 1 0.24 0.70 0.85 1.0 0.541 + 6 2 0.24 0.24 0.85 0.0 0.666 + 7 2 0.24 0.24 0.85 0.0 0.666 + + Modified: + + 22 May 1999 + + Author: + + John Burkardt + +*/ +{ + float a; + float b; + float g; + float h; + int i; + int imat; + int j; + int text_num; + float r; + + text_num = 0; + + fprintf ( fileout, "# %s created by IVREAD.\n", fileout_name ); + fprintf ( fileout, "#\n" ); + fprintf ( fileout, "# Material RGB to Hue map:\n" ); + fprintf ( fileout, "#\n" ); + fprintf ( fileout, "# material R G B Alpha Hue\n" ); + fprintf ( fileout, "#\n" ); + + text_num = text_num + 6; + + for ( j = 0; j < material_num; j++ ) { + r = material_rgba[0][j]; + g = material_rgba[1][j]; + b = material_rgba[2][j]; + a = material_rgba[3][j]; + h = rgb_to_hue ( r, g, b ); + fprintf ( fileout, "# %d %f %f %f %f %f\n", j, r, g, b, a, h ); + text_num = text_num + 1; + } + + fprintf ( fileout, "#\n" ); + fprintf ( fileout, "# The node data is\n" ); + fprintf ( fileout, "# node # / material # / RGBA / Hue\n" ); + fprintf ( fileout, "#\n" ); + text_num = text_num + 4; + + fprintf ( fileout, "%d %d 6 0 0\n", cor3_num, face_num ); + text_num = text_num + 1; + + for ( j = 0; j < cor3_num; j++ ) { + fprintf ( fileout, "%d %f %f %f\n", j, cor3[0][j], cor3[1][j], + cor3[2][j] ); + text_num = text_num + 1; + } +/* + NOTE: + UCD only accepts triangles and quadrilaterals, not higher order + polygons. We would need to break polygons up to proceed. +*/ + for ( j = 0; j < face_num; j++ ) { + + fprintf ( fileout, "%d %d", j, face_material[j] ); + + if ( face_order[j] == 3 ) { + fprintf ( fileout, " tri" ); + } + else if ( face_order[j] == 4 ) { + fprintf ( fileout, " quad" ); + } + else { + fprintf ( fileout, " ???" ); + } + + for ( i = 0; i < face_order[j]; i++ ) { + fprintf ( fileout, "%d", face[i][j] ); + } + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + + } + + fprintf ( fileout, "3 1 4 1\n" ); + fprintf ( fileout, "material, 0...%d\n", material_num - 1 ); + fprintf ( fileout, "RGBA, 0-1/0-1/0-1/0-1\n" ); + fprintf ( fileout, "Hue, 0-1\n" ); + text_num = text_num + 4; + + for ( j = 0; j < cor3_num; j++ ) { + imat = cor3_material[j]; + r = material_rgba[0][imat]; + g = material_rgba[1][imat]; + b = material_rgba[2][imat]; + a = material_rgba[3][imat]; + h = rgb_to_hue ( r, g, b ); + + fprintf ( fileout, "%d %d %f %f %f %f %f\n", j, imat, r, g, b, a, h ); + text_num = text_num + 1; + } +/* + Report. +*/ + printf ( "\n" ); + printf ( "UCD_WRITE - Wrote %d text lines.\n", text_num ); + + return SUCCESS; +} +/******************************************************************************/ + +void vertex_normal_set ( void ) + +/******************************************************************************/ + +/* + Purpose: + + VERTEX_NORMAL_SET recomputes the face vertex normal vectors. + + Modified: + + 12 October 1998 + + Author: + + John Burkardt +*/ +{ + int i; + int i0; + int i1; + int i2; + int iface; + int ivert; + int jp1; + int jp2; + int nfix; + float norm; + float temp; + float x0; + float x1; + float x2; + float xc; + float y0; + float y1; + float y2; + float yc; + float z0; + float z1; + float z2; + float zc; + + if ( face_num <= 0 ) { + return; + } + + nfix = 0; +/* + Consider each face. +*/ + for ( iface = 0; iface < face_num; iface++ ) { + + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + + norm = 0.0; + for ( i = 0; i < 3; i++ ) { + temp = vertex_normal[i][ivert][iface]; + norm = norm + temp * temp; + } + norm = ( float ) sqrt ( norm ); + + if ( norm == 0.0 ) { + + nfix = nfix + 1; + + i0 = face[ivert][iface]; + x0 = cor3[0][i0]; + y0 = cor3[1][i0]; + z0 = cor3[2][i0]; + + jp1 = ivert + 1; + if ( jp1 >= face_order[iface] ) { + jp1 = jp1 - face_order[iface]; + } + i1 = face[jp1][iface]; + x1 = cor3[0][i1]; + y1 = cor3[1][i1]; + z1 = cor3[2][i1]; + + jp2 = ivert + 2; + if ( jp2 >= face_order[iface] ) { + jp2 = jp2 - face_order[iface]; + } + i2 = face[jp2][iface]; + x2 = cor3[0][i2]; + y2 = cor3[1][i2]; + z2 = cor3[2][i2]; + + xc = ( y1 - y0 ) * ( z2 - z0 ) - ( z1 - z0 ) * ( y2 - y0 ); + yc = ( z1 - z0 ) * ( x2 - x0 ) - ( x1 - x0 ) * ( z2 - z0 ); + zc = ( x1 - x0 ) * ( y2 - y0 ) - ( y1 - y0 ) * ( x2 - x0 ); + + norm = ( float ) sqrt ( xc * xc + yc * yc + zc * zc ); + + if ( norm == 0.0 ) { + xc = ( float ) 1.0 / sqrt ( 3.0 ); + yc = ( float ) 1.0 / sqrt ( 3.0 ); + zc = ( float ) 1.0 / sqrt ( 3.0 ); + } + else { + xc = xc / norm; + yc = yc / norm; + zc = zc / norm; + } + + vertex_normal[0][ivert][iface] = xc; + vertex_normal[1][ivert][iface] = yc; + vertex_normal[2][ivert][iface] = zc; + + } + } + } + + if ( nfix > 0 ) { + printf ( "\n" ); + printf ( "VERTEX_NORMAL_SET: Recomputed %d face vertex normals.\n", nfix ); + } + + return; +} +/**********************************************************************/ + +void vertex_to_face_material ( void ) + +/**********************************************************************/ + +/* + Purpose: + + VERTEX_TO_FACE_MATERIAL extends vertex material definitions to faces. + + Discussion: + + Assuming material indices are defined for all the vertices, this + routine assigns to each face the material associated with its + first vertex. + + Modified: + + 22 May 1999 + + Author: + + John Burkardt +*/ +{ + int iface; + int ivert; + + ivert = 0; + for ( iface = 0; iface < face_num; iface++ ) { + face_material[iface] = vertex_material[ivert][iface]; + } + + return; +} +/**********************************************************************/ + +void vertex_to_node_material ( void ) + +/**********************************************************************/ + +/* + Purpose: + + VERTEX_TO_NODE_MATERIAL extends vertex material definitions to nodes. + + Discussion: + + A NODE is a point in space. + A VERTEX is a node as used in a particular face. + One node may be used as a vertex in several faces, or none. + This routine simply runs through all the vertices, and assigns + the material of the vertex to the corresponding node. If a + node appears as a vertex several times, then the node will + end up having the material of the vertex that occurs "last". + + Modified: + + 22 May 1999 + + Author: + + John Burkardt +*/ +{ + int iface; + int ivert; + int node; + + for ( iface = 0; iface < face_num; iface++ ) { + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + node = face[ivert][iface]; + cor3_material[node] = vertex_material[ivert][iface]; + } + } + + return; +} + +/******************************************************************************/ + +int vla_read ( FILE *filein ) + +/******************************************************************************/ + +/* + Purpose: + + VLA_READ reads a VLA file. + + Examples: + + set comment cube.vla created by IVREAD + set comment Original data in cube.iv. + set comment + set intensity EXPLICIT + set parametric NON_PARAMETRIC + set filecontent LINES + set filetype NEW + set depthcue 0 + set defaultdraw stellar + set coordsys RIGHT + set author IVREAD + set site Buhl Planetarium + set library_id UNKNOWN + P 8.59816 5.55317 -3.05561 1.00000 + L 8.59816 2.49756 0.000000E+00 1.00000 + L 8.59816 2.49756 -3.05561 1.00000 + L 8.59816 5.55317 -3.05561 1.00000 + P 8.59816 5.55317 0.000000E+00 1.00000 + ...etc... + L 2.48695 2.49756 -3.05561 1.00000 + + Modified: + + 23 May 1999 + + Author: + + John Burkardt +*/ +{ + int i; + int icor3; + int dup_num; + char *next; + int text_num; + float r1; + float r2; + float r3; + float temp[3]; + char token[LINE_MAX_LEN]; + int width; +/* + Initialize. +*/ + dup_num = 0; + text_num = 0; +/* + Read the next line of the file into INPUT. +*/ + while ( fgets ( input, LINE_MAX_LEN, filein ) != NULL ) { + + text_num = text_num + 1; +/* + Advance to the first nonspace character in INPUT. +*/ + for ( next = input; *next != '\0' && isspace(*next); next++ ) { + } +/* + Skip blank lines and comments. +*/ + if ( *next == '\0' || *next == ';' ) { + continue; + } +/* + Extract the first word in this line. +*/ + sscanf ( next, "%s%n", token, &width ); +/* + Set NEXT to point to just after this token. +*/ + next = next + width; +/* + SET (ignore) +*/ + if ( leqi ( token, "set" ) == TRUE ) { + } +/* + P (begin a line) + L (continue a line) +*/ + else if ( leqi ( token, "P" ) == TRUE || leqi ( token, "L") == TRUE ) { + + if ( leqi ( token, "P" ) == TRUE ) { + if ( line_num > 0 ) { + if ( line_num < LINES_MAX ) { + line_dex[line_num] = -1; + line_material[line_num] = -1; + line_num = line_num + 1; + } + } + } + + sscanf ( next, "%e %e %e", &r1, &r2, &r3 ); + + temp[0] = r1; + temp[1] = r2; + temp[2] = r3; + + if ( cor3_num < 1000 ) { + icor3 = rcol_find ( cor3, 3, cor3_num, temp ); + } + else { + icor3 = -1; + } + + if ( icor3 == -1 ) { + + icor3 = cor3_num; + + if ( cor3_num < COR3_MAX ) { + for ( i = 0; i < 3; i++ ) { + cor3[i][cor3_num] = temp[i]; + } + } + cor3_num = cor3_num + 1; + } + else { + dup_num = dup_num + 1; + } + + if ( line_num < LINES_MAX ) { + line_dex[line_num] = icor3; + line_material[line_num] = 0; + line_num = line_num + 1; + } + } +/* + Unexpected or unrecognized. +*/ + else { + printf ( "\n" ); + printf ( "VLA_READ - Fatal error!\n" ); + printf ( " Unrecognized first word on line.\n" ); + return ERROR; + } + + } + + if ( line_num > 0 ) { + if ( line_num < LINES_MAX ) { + line_dex[line_num] = -1; + line_material[line_num] = -1; + line_num = line_num + 1; + } + } + + return SUCCESS; +} +/******************************************************************************/ + +int vla_write ( FILE *fileout ) + +/******************************************************************************/ + +/* + Purpose: + + VLA_WRITE writes internal graphics information to a VLA file. + + Discussion: + + Comments begin with a semicolon in column 1. + The X, Y, Z coordinates of points begin with a "P" to + denote the beginning of a line, and "L" to denote the + continuation of a line. The fourth entry is intensity, which + should be between 0.0 and 1.0. + + Examples: + + set comment cube.vla created by IVREAD + set comment Original data in cube.iv. + set comment + set intensity EXPLICIT + set parametric NON_PARAMETRIC + set filecontent LINES + set filetype NEW + set depthcue 0 + set defaultdraw stellar + set coordsys RIGHT + set author IVREAD + set site Buhl Planetarium + set library_id UNKNOWN + P 8.59816 5.55317 -3.05561 1.00000 + L 8.59816 2.49756 0.000000E+00 1.00000 + L 8.59816 2.49756 -3.05561 1.00000 + L 8.59816 5.55317 -3.05561 1.00000 + P 8.59816 5.55317 0.000000E+00 1.00000 + ...etc... + L 2.48695 2.49756 -3.05561 1.00000 + + Modified: + + 22 May 1999 + + Author: + + John Burkardt +*/ +{ + char c; + int iline; + float intense = 1.0; + int k; + int text_num; +/* + Initialize. +*/ + text_num = 0; + + fprintf ( fileout, "set comment %s created by IVCON.\n", fileout_name ); + fprintf ( fileout, "set comment Original data in %s.\n", filein_name ); + fprintf ( fileout, "set comment\n" ); + fprintf ( fileout, "set intensity EXPLICIT\n" ); + fprintf ( fileout, "set parametric NON_PARAMETRIC\n" ); + fprintf ( fileout, "set filecontent LINES\n" ); + fprintf ( fileout, "set filetype NEW\n" ); + fprintf ( fileout, "set depthcue 0\n" ); + fprintf ( fileout, "set defaultdraw stellar\n" ); + fprintf ( fileout, "set coordsys RIGHT\n" ); + fprintf ( fileout, "set author IVCON\n" ); + fprintf ( fileout, "set site Buhl Planetarium\n" ); + fprintf ( fileout, "set library_id UNKNOWN\n" ); + + text_num = text_num + 13; + + c = 'P'; + + for ( iline = 0; iline < line_num; iline++ ) { + + k = line_dex[iline]; + + if ( k == -1 ) { + + c = 'P'; + } + else { + + fprintf ( fileout, "%c %f %f %f %f\n", + c, cor3[0][k], cor3[1][k], cor3[2][k], intense ); + + text_num = text_num + 1; + + c = 'L'; + } + } +/* + Report. +*/ + printf ( "\n" ); + printf ( "VLA_WRITE - Wrote %d text lines.\n", text_num ); + + + return SUCCESS; +} + +/**********************************************************************/ + +int wrl_write ( FILE *fileout ) + +/**********************************************************************/ + +/* + Purpose: + + WRL_WRITE writes graphics data to a WRL file. + + Example: + + #VRML V2.0 utf8 + + WorldInfo { + title "cube.iv." + string "WRL file generated by IVREAD. + } + + Group { + children [ + + Shape { + + appearance Appearance { + material Material { + diffuseColor 0.0 0.0 0.0 + emissiveColor 0.0 0.0 0.0 + shininess 1.0 + } + } #end of appearance + + geometry IndexedLineSet { + + coord Coordinate { + point [ + 8.59816 5.55317 -3.05561 + 8.59816 2.49756 0.000000E+00 + ...etc... + 2.48695 2.49756 -3.05561 + ] + } + + coordIndex [ + 0 1 2 -1 3 4 5 6 7 8 - + 9 10 -1 11 12 -1 13 14 15 -1 1 + ...etc... + 191 -1 + ] + + colorPerVertex TRUE + + colorIndex [ + 0 0 0 -1 2 3 1 1 4 7 - + 10 9 -1 7 7 -1 3 2 2 -1 1 + ...etc... + 180 -1 + ] + + } #end of geometry + + } #end of Shape + + ] #end of children + + } #end of Group + + Modified: + + 23 May 1999 + + Author: + + John Burkardt +*/ +{ + int icor3; + int iface; + int itemp; + int ivert; + int j; + int length; + int ndx; + + text_num = 0; + + fprintf ( fileout, "#VRML V2.0 utf8\n" ); + fprintf ( fileout, "\n" ); + fprintf ( fileout, " WorldInfo {\n" ); + fprintf ( fileout, " title \"%s\"\n", fileout_name ); + fprintf ( fileout, " info \"WRL file generated by IVREAD.\"\n" ); + fprintf ( fileout, " info \"Original data in %s\"\n", filein_name ); + fprintf ( fileout, " }\n" ); + fprintf ( fileout, "\n" ); + fprintf ( fileout, " Group {\n" ); + fprintf ( fileout, " children [\n" ); + fprintf ( fileout, " Shape {\n" ); + fprintf ( fileout, " appearance Appearance {\n" ); + fprintf ( fileout, " material Material {\n" ); + fprintf ( fileout, " diffuseColor 0.0 0.0 0.0\n" ); + fprintf ( fileout, " emissiveColor 0.0 0.0 0.0\n" ); + fprintf ( fileout, " shininess 1.0\n" ); + fprintf ( fileout, " }\n" ); + fprintf ( fileout, " }\n" ); + + text_num = text_num + 18; +/* + IndexedLineSet +*/ + if ( line_num > 0 ) { + + fprintf ( fileout, " geometry IndexedLineSet {\n" ); +/* + IndexedLineSet coord +*/ + fprintf ( fileout, " coord Coordinate {\n" ); + fprintf ( fileout, " point [\n" ); + + text_num = text_num + 3; + + for ( icor3 = 0; icor3 < cor3_num; icor3++ ) { + fprintf ( fileout, " %f %f %f\n", cor3[0][icor3], + cor3[1][icor3], cor3[2][icor3] ); + text_num = text_num + 1; + } + + fprintf ( fileout, " ]\n" ); + fprintf ( fileout, " }\n" ); + text_num = text_num + 2; +/* + IndexedLineSet coordIndex. +*/ + fprintf ( fileout, " coordIndex [\n" ); + + text_num = text_num + 1; + + length = 0; + for ( j = 0; j < line_num; j++ ) { + fprintf ( fileout, "%d ", line_dex[j] ); + length = length + 1; + if ( line_dex[j] == -1 || length >= 10 || j == line_num - 1 ) { + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + length = 0; + } + } + + fprintf ( fileout, " ]\n" ); + text_num = text_num + 1; +/* + Colors. (materials) +*/ + fprintf ( fileout, " color Color {\n" ); + fprintf ( fileout, " color [\n" ); + text_num = text_num + 2; + + for ( j = 0; j < material_num; j++ ) { + fprintf ( fileout, " %f %f %f\n", material_rgba[0][j], + material_rgba[1][j], material_rgba[2][j] ); + text_num = text_num + 1; + } + + fprintf ( fileout, " ]\n" ); + fprintf ( fileout, " }\n" ); + fprintf ( fileout, " colorPerVertex TRUE\n" ); +/* + IndexedLineset colorIndex +*/ + fprintf ( fileout, " colorIndex [\n" ); + + text_num = text_num + 4; + + length = 0; + for ( j = 0; j < line_num; j++ ) { + fprintf ( fileout, "%d ", line_material[j] ); + length = length + 1; + if ( line_dex[j] == -1 || length >= 10 || j == line_num - 1 ) { + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + length = 0; + } + } + + fprintf ( fileout, " ]\n" ); + fprintf ( fileout, " }\n" ); + text_num = text_num + 2; + + } +/* + End of IndexedLineSet + + IndexedFaceSet +*/ + if ( face_num > 0 ) { + + fprintf ( fileout, " geometry IndexedFaceSet {\n" ); +/* + IndexedFaceSet coord +*/ + fprintf ( fileout, " coord Coordinate {\n" ); + fprintf ( fileout, " point [\n" ); + + text_num = text_num + 3; + + for ( icor3 = 0; icor3 < cor3_num; icor3++ ) { + fprintf ( fileout, " %f %f %f\n", cor3[0][icor3], + cor3[1][icor3], cor3[2][icor3] ); + + text_num = text_num + 1; + } + + fprintf ( fileout, " ]\n" ); + fprintf ( fileout, " }\n" ); +/* + IndexedFaceSet coordIndex. +*/ + fprintf ( fileout, " coordIndex [\n" ); + + text_num = text_num + 3; + + length = 0; + + for ( iface = 0; iface < face_num; iface++ ) { + + for ( ivert = 0; ivert <= face_order[iface]; ivert++ ) { + + if ( ivert <= face_order[iface] ) { + itemp = face[ivert][iface]; + } + else { + itemp = 0; + } + + fprintf ( fileout, "%d ", itemp ); + length = length + 1; + + if ( itemp == -1 || length >= 10 || + ( iface == face_num - 1 && ivert == face_order[iface] ) ) { + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + length = 0; + } + + } + + } + + fprintf ( fileout, " ]\n" ); + text_num = text_num + 1; +/* + IndexedFaceset colorIndex +*/ + fprintf ( fileout, " colorIndex [\n" ); + text_num = text_num + 1; + + length = 0; + ndx = 0; + + for ( iface = 0; iface < face_num; iface++ ) { + + for ( ivert = 0; ivert <= face_order[iface]; ivert++ ) { + + if ( ivert <= face_order[iface] ) { + itemp = vertex_material[ivert][iface]; + ndx = ndx + 1; + } + else { + itemp = 0; + } + + fprintf ( fileout, "%d ", itemp ); + length = length + 1; + + if ( itemp == -1 || length >= 10 || + ( iface == face_num - 1 && ivert == face_order[iface] ) ) { + + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + length = 0; + + } + + } + + } + + fprintf ( fileout, " ]\n" ); + fprintf ( fileout, " }\n" ); + text_num = text_num + 2; + + } +/* + End of IndexedFaceSet + + End of: + Shape + children + Group +*/ + fprintf ( fileout, " }\n" ); + fprintf ( fileout, " ]\n" ); + fprintf ( fileout, " }\n" ); + + text_num = text_num + 3; +/* + Report. +*/ + printf ( "\n" ); + printf ( "WRL_WRITE - Wrote %d text lines.\n", text_num ); + + return SUCCESS; +} +/******************************************************************************/ + +int xgl_write ( FILE *fileout ) + +/******************************************************************************/ + +/* + Purpose: + + XGL_WRITE writes an XGL file. + + Discussion: + + Two corrections to the routine were pointed out by + Mike Phillips, msphil@widowmaker.com, on 17 September 2001, + and are gratefully acknowledged. + + Example: + + + + + 0.1, 0.1, 0.1 + + + + 0.2, 0.1, 0.1 + + 0.1, 0.2, 0.1 + 0, 0, 100 + 0.1, 0.1, 0.2 + + + + + +

-0.5, -0.5, 1

+

0.5, -0.5, 1

+

0.5, 0.5, 1

+

-0.5, 0.5, 1

+

0.5, -0.5, 0

+

-0.5, -0.5, 0

+

-0.5, 0.5, 0

+

0.5, 0.5, 0

+ + -0.408248, -0.408248, 0.816497 + 0.666667, -0.666667, 0.333333 + 0.408248, 0.408248, 0.816497 + -0.666667, 0.666667, 0.333333 + 0.408248, -0.408248, -0.816497 + -0.666667, -0.666667, -0.333333 + -0.408248, 0.408248, -0.816497 + 0.666667, 0.666667, -0.333333 + + + 0.9 + 0.1, 0.1, 0.1 + 0.2, 0.1, 0.1 + 0.1, 0.2, 0.1 + 0.8 + 0.1, 0.1, 0.2 + + + + 0 + 0 0 + 1 1 + 2 2 + + + 0 + 0 0 + 2 2 + 3 3 + + + 0 + 4 4 + 5 5 + 6 6 + + + 0 + 4 4 + 6 6 + 7 7 + + + 0 + 5 5 + 0 0 + 3 3 + + + 0 + 5 5 + 3 3 + 6 6 + + + 0 + 1 1 + 4 4 + 7 7 + + + 0 + 1 1 + 7 7 + 2 2 + + + 0 + 5 5 + 4 4 + 1 1 + + + 0 + 5 5 + 1 1 + 0 0 + + + 0 + 3 3 + 2 2 + 7 7 + + + 0 + 3 3 + 7 7 + 6 6 + +
+ + + + 0, 0, 0 + 0, 0, 0 + 1, 1, 1 + 1, 1, 1 + + 0 + + +
+ + Reference: + + XGL specification at http://www.xglspec.org/ + + Modified: + + 17 September 2001 + + Author: + + John Burkardt +*/ +{ + int iface; + int ivert; + int j; + float light_ambient_rgb[3]; + float light_diffuse_rgb[3]; + float light_direction[3]; + float light_specular_rgb[3]; + int material; + float material_alpha; + float material_amb_rgb[3]; + float material_diff_rgb[3]; + float material_emiss_rgb[3]; + float material_shine; + float material_spec_rgb[3]; + int mesh; + int mesh_num = 1; + int object; + float transform_forward[3]; + float transform_position[3]; + float transform_scale[3]; + float transform_up[3]; +/* + Make up some placeholder values for now. +*/ + light_ambient_rgb[0] = 0.2; + light_ambient_rgb[1] = 0.1; + light_ambient_rgb[2] = 0.1; + + light_diffuse_rgb[0] = 0.1; + light_diffuse_rgb[1] = 0.2; + light_diffuse_rgb[2] = 0.1; + + light_direction[0] = 0.0; + light_direction[1] = 0.0; + light_direction[2] = 100.0; + + light_specular_rgb[0] = 0.1; + light_specular_rgb[1] = 0.1; + light_specular_rgb[2] = 0.2; + + material_alpha = 0.9; + + material_amb_rgb[0] = 0.1; + material_amb_rgb[1] = 0.1; + material_amb_rgb[2] = 0.1; + + material_diff_rgb[0] = 0.2; + material_diff_rgb[1] = 0.1; + material_diff_rgb[2] = 0.1; + + material_emiss_rgb[0] = 0.1; + material_emiss_rgb[1] = 0.2; + material_emiss_rgb[2] = 0.1; + + material_shine = 0.8; + + material_spec_rgb[0] = 0.1; + material_spec_rgb[1] = 0.1; + material_spec_rgb[2] = 0.2; + + transform_forward[0] = 0.0; + transform_forward[1] = 0.0; + transform_forward[2] = 0.0; + + transform_position[0] = 0.0; + transform_position[1] = 0.0; + transform_position[2] = 0.0; + + transform_scale[0] = 1.0; + transform_scale[1] = 1.0; + transform_scale[2] = 1.0; + + transform_up[0] = 1.0; + transform_up[1] = 1.0; + transform_up[2] = 1.0; + + object_num = 1; + + text_num = 0; + + fprintf ( fileout, "\n" ); + fprintf ( fileout, "\n" ); + + text_num = text_num + 2; + + fprintf ( fileout, " \n" ); + fprintf ( fileout, " %f, %f, %f \n", + background_rgb[0], background_rgb[1], background_rgb[2] ); + fprintf ( fileout, " \n" ); + fprintf ( fileout, "\n" ); + fprintf ( fileout, " \n" ); + fprintf ( fileout, " %f, %f, %f \n", + light_ambient_rgb[0], light_ambient_rgb[1], light_ambient_rgb[2] ); + fprintf ( fileout, " \n" ); + fprintf ( fileout, " %f, %f, %f \n", + light_diffuse_rgb[0], light_diffuse_rgb[1], light_diffuse_rgb[2] ); + fprintf ( fileout, " %f, %f, %f \n", + light_direction[0], light_direction[1], light_direction[2] ); + fprintf ( fileout, " %f, %f, %f \n", + light_specular_rgb[0], light_specular_rgb[1], light_specular_rgb[2] ); + fprintf ( fileout, " \n" ); + fprintf ( fileout, " \n" ); + + text_num = text_num + 12; + + for ( mesh = 0; mesh < mesh_num; mesh++ ) { + + fprintf ( fileout, "\n" ); + fprintf ( fileout, " \n", mesh ); + fprintf ( fileout, "\n" ); + text_num = text_num + 3; + + for ( j = 0; j < cor3_num; j++ ) { + fprintf ( fileout, "

%f, %f, %f

\n", j, + cor3[0][j], cor3[1][j], cor3[2][j] ); + text_num = text_num + 1; + } + + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + for ( j = 0; j < cor3_num; j++ ) { + fprintf ( fileout, " %f, %f, %f \n", j, + cor3_normal[0][j], cor3_normal[1][j], cor3_normal[2][j] ); + text_num = text_num + 1; + } + + for ( material = 0; material < material_num; material++ ) { + fprintf ( fileout, "\n" ); + fprintf ( fileout, " \n", material ); + fprintf ( fileout, " %f \n", material_alpha ); + fprintf ( fileout, " %f, %f, %f \n", + material_amb_rgb[0], material_amb_rgb[1], material_amb_rgb[2] ); + fprintf ( fileout, " %f, %f, %f \n", + material_diff_rgb[0], material_diff_rgb[1], material_diff_rgb[2] ); + fprintf ( fileout, " %f, %f, %f \n", + material_emiss_rgb[0], material_emiss_rgb[1], material_emiss_rgb[2] ); + fprintf ( fileout, " %f \n", material_shine ); + fprintf ( fileout, " %f, %f, %f \n", + material_spec_rgb[0], material_spec_rgb[1], material_spec_rgb[2] ); + fprintf ( fileout, " \n" ); + text_num = text_num + 9; + } + + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + + for ( iface = 0; iface < face_num; iface++ ) { + fprintf ( fileout, " \n" ); + fprintf ( fileout, " %d \n", face_material[iface] ); + text_num = text_num + 2; + for ( ivert = 0; ivert < face_order[iface]; ivert++ ) { + fprintf ( fileout, + " %d %d \n", + ivert+1, face[ivert][iface], face[ivert][iface], ivert+1 ); + text_num = text_num + 1; + } + fprintf ( fileout, " \n" ); + text_num = text_num + 1; + } + + fprintf ( fileout, "
\n" ); + text_num = text_num + 1; + + } + + fprintf ( fileout, "\n" ); + text_num = text_num + 1; + + for ( object = 0; object < object_num; object++ ) { + + fprintf ( fileout, " \n" ); + fprintf ( fileout, " \n" ); + fprintf ( fileout, " %f, %f, %f \n", + transform_forward[0], transform_forward[1], transform_forward[2] ); + fprintf ( fileout, " %f, %f, %f \n", + transform_position[0], transform_position[1], transform_position[2] ); + fprintf ( fileout, "' %f, %f, %f \n", + transform_scale[0], transform_scale[1], transform_scale[2] ); + fprintf ( fileout, " %f, %f, %f \n", + transform_up[0], transform_up[1], transform_up[2] ); + fprintf ( fileout, " \n" ); + mesh = 0; + fprintf ( fileout, " %d \n", mesh ); + fprintf ( fileout, " \n" ); + text_num = text_num + 9; + + } + + fprintf ( fileout, "\n" ); + fprintf ( fileout, "
\n" ); + text_num = text_num + 2; + +/* + Report. +*/ + printf ( "\n" ); + printf ( "XGL_WRITE - Wrote %d text lines.\n", text_num ); + + return SUCCESS; +} diff --git a/kdl_parser/CMakeLists.txt b/kdl_parser/CMakeLists.txt new file mode 100644 index 0000000..2bd8fce --- /dev/null +++ b/kdl_parser/CMakeLists.txt @@ -0,0 +1,38 @@ +cmake_minimum_required(VERSION 2.4.6) +include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) + +# Set the build type. Options are: +# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage +# Debug : w/ debug symbols, w/o optimization +# Release : w/o debug symbols, w/ optimization +# RelWithDebInfo : w/ debug symbols, w/ optimization +# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries +#set(ROS_BUILD_TYPE RelWithDebInfo) + +rosbuild_init() + +rosbuild_add_boost_directories() + +#set the default path for built executables to the "bin" directory +set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) +#set the default path for built libraries to the "lib" directory +set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) + +#uncomment if you have defined messages +#genmsg() +#uncomment if you have defined services +#gensrv() + +rosbuild_add_library(${PROJECT_NAME} src/xml_parser.cpp src/dom_parser.cpp) + +rosbuild_add_executable(example_xml test/example_xml.cpp ) +target_link_libraries(example_xml ${PROJECT_NAME}) + +rosbuild_add_executable(example_dom test/example_dom.cpp ) +target_link_libraries(example_dom ${PROJECT_NAME}) + +rosbuild_add_executable(test_parser test/test_kdl_parser.cpp ) +target_link_libraries(test_parser ${PROJECT_NAME}) + +rosbuild_add_gtest_build_flags(test_parser) +rosbuild_add_rostest(${PROJECT_SOURCE_DIR}/test/test_kdl_parser.launch) diff --git a/kdl_parser/Makefile b/kdl_parser/Makefile new file mode 100644 index 0000000..b75b928 --- /dev/null +++ b/kdl_parser/Makefile @@ -0,0 +1 @@ +include $(shell rospack find mk)/cmake.mk \ No newline at end of file diff --git a/kdl_parser/include/kdl_parser/dom_parser.hpp b/kdl_parser/include/kdl_parser/dom_parser.hpp new file mode 100644 index 0000000..2e91c47 --- /dev/null +++ b/kdl_parser/include/kdl_parser/dom_parser.hpp @@ -0,0 +1,54 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#ifndef DOM_PARSER_H +#define DOM_PARSER_H + +#include +#include +#include + +using namespace std; + +namespace kdl_parser{ + +bool treeFromFile(const string& file, KDL::Tree& tree); +bool treeFromString(const string& xml, KDL::Tree& tree); +bool treeFromXml(TiXmlDocument *xml_doc, KDL::Tree& tree); +bool treeFromRobotModel(urdf::Model& robot_model, KDL::Tree& tree); +} + +#endif diff --git a/kdl_parser/include/kdl_parser/xml_parser.hpp b/kdl_parser/include/kdl_parser/xml_parser.hpp new file mode 100644 index 0000000..89e77e9 --- /dev/null +++ b/kdl_parser/include/kdl_parser/xml_parser.hpp @@ -0,0 +1,53 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#ifndef XML_PARSER_H +#define XML_PARSER_H + +#include +#include +#include + +using namespace std; + +namespace KDL{ + +bool treeFromFile(const string& file, Tree& tree); +bool treeFromString(const string& xml, Tree& tree); +bool treeFromXml(TiXmlElement *root, Tree& tree); +} + +#endif diff --git a/kdl_parser/manifest.xml b/kdl_parser/manifest.xml new file mode 100644 index 0000000..571b60e --- /dev/null +++ b/kdl_parser/manifest.xml @@ -0,0 +1,23 @@ + + + + The Kinematics and Dynamics Library (KDL) defines a tree structure to represent the kinematic and dynamic parameters of a robot mechanism. This package provides tools to construct a KDL tree from the robot representation in the urdf package. + + + Wim Meeussen meeussen@willowgarage.com + BSD + + http://pr.willowgarage.com/wiki/ + + + + + + + + + + + + + diff --git a/kdl_parser/pr2.urdf b/kdl_parser/pr2.urdf new file mode 100644 index 0000000..45e35f9c --- /dev/null +++ b/kdl_parser/pr2.urdf @@ -0,0 +1,2542 @@ + + + + + + + + + + + + + + + + + + + true + 1000.0 + + + + + + true + 1.0 + 5 + -10.0 + 1.0 + 10.0 + 1200000.0 + diagnostic + battery_state + self_test + + + + + true + 1000.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + fl_caster_l_wheel_collision + 100.0 + + true + 100.0 + fl_caster_l_wheel_bumper + + + + + + + + + + + + + + 75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + fl_caster_r_wheel_collision + 100.0 + + true + 100.0 + fl_caster_r_wheel_bumper + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + fr_caster_l_wheel_collision + 100.0 + + true + 100.0 + fr_caster_l_wheel_bumper + + + + + + + + + + + + + + 75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + fr_caster_r_wheel_collision + 100.0 + + true + 100.0 + fr_caster_r_wheel_bumper + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + bl_caster_l_wheel_collision + 100.0 + + true + 100.0 + bl_caster_l_wheel_bumper + + + + + + + + + + + + + + 75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + bl_caster_r_wheel_collision + 100.0 + + true + 100.0 + bl_caster_r_wheel_bumper + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + br_caster_l_wheel_collision + 100.0 + + true + 100.0 + br_caster_l_wheel_bumper + + + + + + + + + + + + + + 75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + br_caster_r_wheel_collision + 100.0 + + true + 100.0 + br_caster_r_wheel_bumper + + + + + + + + + + + + + + -75.05 + + + base_collision + 100.0 + + true + 100.0 + base_bumper + + + + + + + + + + true + 100.0 + base_link + base_pose_ground_truth + 0.01 + map + 25.7 25.7 0 + 0 0 0 + + + + + 640 + 640 + 1 + 0.0 0.0 0.0 + false + + -100 + 100 + + 0.05 + 10.0 + 0.01 + 20.0 + + 0.005 + true + 20.0 + base_scan + base_laser + + + + + + + + true + 100.0 + plug_magnet + plug_magnet_pose_ground_truth + 0.01 + map + 0 0 0 + 0 0 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -52143.33 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 6.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 6.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_shoulder_pan_collision + 100.0 + + true + 100.0 + r_shoulder_pan_bumper + + + + + true + + + + + r_shoulder_lift_collision_geom + 100.0 + + true + 100.0 + r_r_shoulder_lift_bumper + + + + true + + + + + + true + + + + + + r_upper_arm_collision_geom + 100.0 + + true + 100.0 + r_upper_arm_bumper + + + + true + + + + r_elbow_flex_collision_geom + 100.0 + + true + 100.0 + r_elbow_flex_bumper + + + + + + + true + + + + true + + true + + r_forearm_collision + 100.0 + + true + 100.0 + r_forearm_bumper + + + + + + true + + r_wrist_flex_collision + 100.0 + + true + 100.0 + r_wrist_flex_bumper + + + + + + + + true + + r_wrist_roll_collision + 100.0 + + true + 100.0 + r_wrist_roll_bumper + + + + + + + + + 63.16 + + + + 61.89 + + + + 32.65 + + + + -36.17 + + + + 90.5142857143 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + + r_gripper_l_finger_collision + 100.0 + + true + 100.0 + r_gripper_l_finger_bumper + + + + + + + + + + + + + + + true + + r_gripper_r_finger_collision + 100.0 + + true + 100.0 + r_gripper_r_finger_bumper + + + + + + + + + + + + + + + + + + true + + + r_gripper_l_finger_tip_collision + 100.0 + + true + 100.0 + r_gripper_l_finger_tip_bumper + + + + + + + + + + + + + + + + + true + + + r_gripper_r_finger_tip_collision + 100.0 + + true + 100.0 + r_gripper_r_finger_tip_bumper + + + + + + + + + + + + + + + + + true + 100.0 + r_gripper_l_finger_link + r_gripper_l_finger_pose_ground_truth + 0.0 + map + + + + true + 100.0 + r_gripper_l_finger_link + r_gripper_l_finger_force_ground_truth + r_gripper_l_finger_link + + + + + + + + + + + + + + + + true + + r_gripper_palm_collision + 100.0 + + true + 100.0 + r_gripper_palm_bumper + + + + + + true + + + r_gripper_l_finger_tip_link + r_gripper_float_link + r_gripper_l_finger_tip_link + 0 1 0 + 0 0 0 + + + r_gripper_r_finger_tip_link + r_gripper_float_link + r_gripper_r_finger_tip_link + 0 1 0 + 0 0 0 + + + + + true + 100.0 + r_gripper_palm_link + r_gripper_palm_pose_ground_truth + 0 0 0 + 0 0 0 + 0.0 + map + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + l_shoulder_pan_collision + 100.0 + + true + 100.0 + l_shoulder_pan_bumper + + + + + true + + + + + l_shoulder_lift_collision_geom + 100.0 + + true + 100.0 + l_r_shoulder_lift_bumper + + + + true + + + + + + true + + + + + + l_upper_arm_collision_geom + 100.0 + + true + 100.0 + l_upper_arm_bumper + + + + true + + + + l_elbow_flex_collision_geom + 100.0 + + true + 100.0 + l_elbow_flex_bumper + + + + + + + true + + + + true + + true + + l_forearm_collision + 100.0 + + true + 100.0 + l_forearm_bumper + + + + + + true + + l_wrist_flex_collision + 100.0 + + true + 100.0 + l_wrist_flex_bumper + + + + + + + + true + + l_wrist_roll_collision + 100.0 + + true + 100.0 + l_wrist_roll_bumper + + + + + + + + + 63.16 + + + + 61.89 + + + + 32.65 + + + + -36.17 + + + + 90.5142857143 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + + l_gripper_l_finger_collision + 100.0 + + true + 100.0 + l_gripper_l_finger_bumper + + + + + + + + + + + + + + + true + + l_gripper_r_finger_collision + 100.0 + + true + 100.0 + l_gripper_r_finger_bumper + + + + + + + + + + + + + + + + + + true + + + l_gripper_l_finger_tip_collision + 100.0 + + true + 100.0 + l_gripper_l_finger_tip_bumper + + + + + + + + + + + + + + + + + true + + + l_gripper_r_finger_tip_collision + 100.0 + + true + 100.0 + l_gripper_r_finger_tip_bumper + + + + + + + + + + + + + + + + + true + 100.0 + l_gripper_l_finger_link + l_gripper_l_finger_pose_ground_truth + 0.0 + map + + + + true + 100.0 + l_gripper_l_finger_link + l_gripper_l_finger_force_ground_truth + l_gripper_l_finger_link + + + + + + + + + + + + + + + + true + + l_gripper_palm_collision + 100.0 + + true + 100.0 + l_gripper_palm_bumper + + + + + + true + + + l_gripper_l_finger_tip_link + l_gripper_float_link + l_gripper_l_finger_tip_link + 0 1 0 + 0 0 0 + + + l_gripper_r_finger_tip_link + l_gripper_float_link + l_gripper_r_finger_tip_link + 0 1 0 + 0 0 0 + + + + + true + 100.0 + l_gripper_palm_link + l_gripper_palm_pose_ground_truth + 0 0 0 + 0 0 0 + 0.0 + map + + + + true + + + + + + + + + + + + + + + + + + + + + diff --git a/kdl_parser/src/dom_parser.cpp b/kdl_parser/src/dom_parser.cpp new file mode 100644 index 0000000..a9b75dd --- /dev/null +++ b/kdl_parser/src/dom_parser.cpp @@ -0,0 +1,173 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#include "kdl_parser/dom_parser.hpp" +#include + + +using namespace std; +using namespace KDL; + +namespace kdl_parser{ + + +// construct vector +Vector toKdl(urdf::Vector3 v) +{ + return Vector(v.x, v.y, v.z); +} + +// construct rotation +Rotation toKdl(urdf::Rotation r) +{ + double roll, pitch, yaw; + r.getRPY(roll, pitch, yaw); + return Rotation::RPY(roll, pitch, yaw); +} + +// construct pose +Frame toKdl(urdf::Pose p) +{ + return Frame(toKdl(p.rotation), toKdl(p.position)); +} + +// construct joint +Joint toKdl(boost::shared_ptr jnt) +{ + Frame F_parent_jnt = toKdl(jnt->parent_to_joint_origin_transform); + + switch (jnt->type){ + case urdf::Joint::FIXED:{ + return Joint(jnt->name, Joint::None); + } + case urdf::Joint::REVOLUTE:{ + Vector axis = toKdl(jnt->axis); + return Joint(jnt->name, F_parent_jnt.p, F_parent_jnt.M * axis, Joint::RotAxis); + } + case urdf::Joint::CONTINUOUS:{ + Vector axis = toKdl(jnt->axis); + return Joint(jnt->name, F_parent_jnt.p, F_parent_jnt.M * axis, Joint::RotAxis); + } + case urdf::Joint::PRISMATIC:{ + Vector axis = toKdl(jnt->axis); + return Joint(jnt->name, F_parent_jnt.p, F_parent_jnt.M * axis, Joint::TransAxis); + } + default:{ + return Joint(jnt->name, Joint::None); + } + } + return Joint(); +} + +// construct inertia +RigidBodyInertia toKdl(boost::shared_ptr i) +{ + Frame origin = toKdl(i->origin); + return origin.M * RigidBodyInertia(i->mass, origin.p, RotationalInertia(i->ixx, i->iyy, i->izz, i->ixy, i->ixz, i->iyz)); +} + + +// recursive function to walk through tree +bool addChildrenToTree(boost::shared_ptr root, Tree& tree) +{ + std::vector > children = root->child_links; + ROS_DEBUG("Link %s had %i children", root->name.c_str(), children.size()); + + // constructs the optional inertia + RigidBodyInertia inert(0); + if (root->inertial) + inert = toKdl(root->inertial); + + // constructs the kdl joint + Joint jnt = toKdl(root->parent_joint); + + // construct the kdl segment + Segment sgm(root->name, jnt, toKdl(root->parent_joint->parent_to_joint_origin_transform)); + + // add segment to tree + tree.addSegment(sgm, root->parent_joint->parent_link_name); + + // recurslively add all children + for (size_t i=0; iname); + + // add all children + for (size_t i=0; ichild_links.size(); i++) + if (!addChildrenToTree(robot_model.getRoot()->child_links[i], tree)) + return false; + + return true; +} + + + +} + diff --git a/kdl_parser/src/xml_parser.cpp b/kdl_parser/src/xml_parser.cpp new file mode 100644 index 0000000..785577a --- /dev/null +++ b/kdl_parser/src/xml_parser.cpp @@ -0,0 +1,365 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#include +#include "kdl_parser/xml_parser.hpp" + +using namespace std; + +namespace KDL{ + + +bool isNumber(const char& c) +{ + return (c=='1' || c=='2' ||c=='3' ||c=='4' ||c=='5' ||c=='6' ||c=='7' ||c=='8' ||c=='9' ||c=='0' ||c=='.' ||c=='-' ||c==' '); +} + +bool isNumber(const std::string& s) +{ + for (unsigned int i=0; iAttribute(name.c_str()); + if (!attr_char){ + cerr << "No " << name << " found in xml" << endl; + return false; + } + attr = string(attr_char); + return true; +} + + +bool getVector(TiXmlElement *vector_xml, const string& field, Vector& vector) +{ + if (!vector_xml) return false; + string vector_str; + if (!getAtribute(vector_xml, field, vector_str)) + return false; + + std::vector pieces; + boost::split( pieces, vector_str, boost::is_any_of(" ")); + unsigned int pos=0; + for (unsigned int i = 0; i < pieces.size(); ++i){ + if (pieces[i] != ""){ + if (pos < 3){ + if (!isNumber(pieces[i])) + {cerr << "This is not a valid number: '" << pieces[i] << "'" << endl; return false;} + vector(pos) = atof(pieces[i].c_str()); + } + pos++; + } + } + + if (pos != 3) { + cerr << "Vector did not contain 3 pieces:" << endl; + pos = 1; + for (unsigned int i = 0; i < pieces.size(); ++i){ + if (pieces[i] != ""){ + cerr << " " << pos << ": '" << pieces[i] << "'" << endl; + pos++; + } + } + return false; + } + + return true; +} + +bool getValue(TiXmlElement *value_xml, const string& field, double& value) +{ + if (!value_xml) return false; + string value_str; + if (!getAtribute(value_xml, field, value_str)) return false; + + if (!isNumber(value_str)) + {cerr << "This is not a valid number: '" << value_str << "'" << endl; return false;} + value = atof(value_str.c_str()); + + return true; +} + + +bool getFrame(TiXmlElement *frame_xml, Frame& frame) +{ + if (!frame_xml) return false; + + Vector origin, rpy; + if (!getVector(frame_xml, "xyz", origin)) + {cerr << "Frame does not have xyz" << endl; return false;} + if (!getVector(frame_xml, "rpy", rpy)) + {cerr << "Frame does not have rpy" << endl; return false;} + + frame = Frame(Rotation::RPY(rpy(0), rpy(1), rpy(2)), origin); + return true; +} + + +bool getRotInertia(TiXmlElement *rot_inertia_xml, RotationalInertia& rot_inertia) +{ + if (!rot_inertia_xml) return false; + double Ixx=0, Iyy=0, Izz=0, Ixy=0, Ixz=0, Iyz=0; + if (!getValue(rot_inertia_xml, "ixx", Ixx)) return false; + if (!getValue(rot_inertia_xml, "iyy", Iyy)) return false; + if (!getValue(rot_inertia_xml, "izz", Izz)) return false; + if (!getValue(rot_inertia_xml, "ixy", Ixy)) return false; + if (!getValue(rot_inertia_xml, "ixz", Ixz)) return false; + if (!getValue(rot_inertia_xml, "iyz", Iyz)) return false; + + rot_inertia = RotationalInertia(Ixx, Iyy, Izz, Ixy, Ixz, Iyz); + return true; +} + + +bool getInertia(TiXmlElement *inertia_xml, RigidBodyInertia& inertia) +{ + if (!inertia_xml) return false; + Vector cog; + if (!getVector(inertia_xml->FirstChildElement("com"), "xyz", cog)) + {cerr << "Inertia does not specify center of gravity" << endl; return false;} + double mass = 0.0; + if (!getValue(inertia_xml->FirstChildElement("mass"), "value", mass)) + {cerr << "Inertia does not specify mass" << endl; return false;} + RotationalInertia rot_inertia; + if (!getRotInertia(inertia_xml->FirstChildElement("inertia"), rot_inertia)) + {cerr << "Inertia does not specify rotational inertia" << endl; return false;} + inertia = RigidBodyInertia(mass, cog, rot_inertia); + return true; +} + + + +bool getJoint(TiXmlElement *joint_xml, Joint& joint) +{ + if (!joint_xml) return false; + // get joint name + string joint_name; + if (!getAtribute(joint_xml, "name", joint_name)) + {cerr << "Joint does not have name" << endl; return false;} + + // get joint type + string joint_type; + if (!getAtribute(joint_xml, "type", joint_type)) + {cerr << "Joint does not have type" << endl; return false;} + + if (joint_type == "revolute"){ + Vector axis, origin; + // mandatory axis + if (!getVector(joint_xml->FirstChildElement("axis"), "xyz", axis)) + {cerr << "Revolute joint does not spacify axis" << endl; return false;} + // optional origin + if (!getVector(joint_xml->FirstChildElement("anchor"), "xyz", origin)) + origin = Vector::Zero(); + joint = Joint(joint_name, origin, axis, Joint::RotAxis); + } + else if (joint_type == "prismatic"){ + Vector axis, origin; + // mandatory axis + if (!getVector(joint_xml->FirstChildElement("axis"), "xyz", axis)) + {cerr << "Prismatic joint does not spacify axis" << endl; return false;}; + // optional origin + if (!getVector(joint_xml->FirstChildElement("anchor"), "xyz", origin)) + origin = Vector::Zero(); + joint = Joint(joint_name, origin, axis, Joint::TransAxis); + } + else if (joint_type == "fixed"){ + joint = Joint(joint_name, Joint::None); + } + else{ + cerr << "Unknown joint type '" << joint_type << "'. Using fixed joint instead" << endl; + joint = Joint(joint_name, Joint::None); + } + + return true; +} + + +bool getSegment(TiXmlElement *segment_xml, map& joints, Segment& segment) +{ + if (!segment_xml) return false; + // get segment name + string segment_name; + if (!getAtribute(segment_xml, "name", segment_name)) + {cerr << "Segment does not have name" << endl; return false;} + + // get mandetory frame + Frame frame; + if (!getFrame(segment_xml->FirstChildElement("origin"), frame)) + {cerr << "Segment does not have origin" << endl; return false;} + + // get mandetory joint + string joint_name; + if (!getAtribute(segment_xml->FirstChildElement("joint"), "name", joint_name)) + {cerr << "Segment does not specify joint name" << endl; return false;} + + Joint joint; + map::iterator it = joints.find(joint_name); + if (it != joints.end()) + joint = it->second; + else if (getJoint(segment_xml->FirstChildElement("joint"), joint)); + else {cerr << "Could not find joint " << joint_name << " in segment" << endl; return false;} + + if (joint.getType() != Joint::None) + joint = Joint(joint_name, frame*(joint.JointOrigin()), joint.JointAxis(), joint.getType()); + + // get optional inertia + RigidBodyInertia inertia(0.0); + getInertia(segment_xml->FirstChildElement("inertial"), inertia); + + segment = Segment(segment_name, joint, frame, inertia); + return true; +} + + +void addChildrenToTree(const string& root, const map& segments, const map& parents, Tree& tree) +{ + // add root segments + if (tree.addSegment(segments.find(root)->second, parents.find(root)->second)){ + cout << "Added segment " << root << " to " << parents.find(root)->second << endl; + + // find children + for (map::const_iterator p=parents.begin(); p!=parents.end(); p++) + if (p->second == root) addChildrenToTree(p->first, segments, parents, tree); + } + else {cerr << "Failed to add segment to tree" << endl;} +} + + +bool getTree(TiXmlElement *robot_xml, Tree& tree) +{ + cout << "Parsing robot xml" << endl; + + if (!robot_xml) return false; + + // Constructs the joints + TiXmlElement *joint_xml = NULL; + Joint joint; + map joints; + for (joint_xml = robot_xml->FirstChildElement("joint"); joint_xml; joint_xml = joint_xml->NextSiblingElement("joint")){ + // get joint name + string joint_name; + if (!getAtribute(joint_xml, "name", joint_name)) + {cerr << "Joint does not have name" << endl; return false;} + + // build joint + if (!getJoint(joint_xml, joint)) + {cerr << "Constructing joint " << joint_name << " failed" << endl; return false;} + joints[joint.getName()] = joint; + } + + // Constructs the segments + TiXmlElement *segment_xml = NULL; + Segment segment; + map segments; + map parents; + for (segment_xml = robot_xml->FirstChildElement("link"); segment_xml; segment_xml = segment_xml->NextSiblingElement("link")){ + + // get segment name + string segment_name; + if (!getAtribute(segment_xml, "name", segment_name)) + {cerr << "Segment does not have name" << endl; return false;} + + // get segment parent + string segment_parent; + if (!getAtribute(segment_xml->FirstChildElement("parent"), "name", segment_parent)) + {cerr << "Segment " << segment_name << " does not have parent" << endl; return false;} + + // build segment + if (!getSegment(segment_xml, joints, segment)) + {cerr << "Constructing segment " << segment_name << " failed" << endl; return false;} + segments[segment.getName()] = segment; + parents[segment.getName()] = segment_parent; + } + + // fail if no segments were found + if (segments.empty()){ + cerr << "Did not find any segments" << endl; + return false; + } + + // find the root segment: the parent segment that does not exist + string root; + for (map::const_iterator p=parents.begin(); p!=parents.end(); p++) + if (segments.find(p->second) == segments.end()) + root = p->first; + cout << parents[root] << " is root segment " << endl; + tree = Tree(parents[root]); + + // add all segments to tree + addChildrenToTree(root, segments, parents, tree); + + return true; +} + + +bool treeFromFile(const string& file, Tree& tree) +{ + TiXmlDocument urdf_xml; + urdf_xml.LoadFile(file); + TiXmlElement *root = urdf_xml.FirstChildElement("robot"); + if (!root){ + cerr << "Could not parse the xml" << endl; + return false; + } + return getTree(root, tree); +} + + +bool treeFromString(const string& xml, Tree& tree) +{ + TiXmlDocument urdf_xml; + urdf_xml.Parse(xml.c_str()); + TiXmlElement *root = urdf_xml.FirstChildElement("robot"); + if (!root){ + cerr << "Could not parse the xml" << endl; + return false; + } + return getTree(root, tree); +} + + +bool treeFromXml(TiXmlElement *root, Tree& tree) +{ + return getTree(root, tree); +} + +} + diff --git a/kdl_parser/test/example_dom.cpp b/kdl_parser/test/example_dom.cpp new file mode 100644 index 0000000..f19f718 --- /dev/null +++ b/kdl_parser/test/example_dom.cpp @@ -0,0 +1,105 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#include +#include +#include "kdl_parser/dom_parser.hpp" +#include + +using namespace KDL; +using namespace std; +using namespace urdf; + +int main() +{ + Model robot_model; + if (!robot_model.initFile("pr2.urdf")) + {cerr << "Could not generate robot model" << endl; return false;} + + Tree my_tree; + if (!kdl_parser::treeFromRobotModel(robot_model, my_tree)) + {cerr << "Could not extract kdl tree" << endl; return false;} + + // walk through tree + cout << " ======================================" << endl; + SegmentMap::const_iterator root = my_tree.getRootSegment(); + cout << "Found root segment '" << root->second.segment.getName() << "' with " << root->second.children.size() << " children" << endl; + for (unsigned int i=0; isecond.children.size(); i++){ + SegmentMap::const_iterator child = root->second.children[i]; + cout << " - child " << i+1 << ": " << child->second.segment.getName() << " has joint " << child->second.segment.getJoint().getName() + << " and " << child->second.children.size() << " children" << endl; + + for (unsigned int j=0; jsecond.children.size(); j++){ + SegmentMap::const_iterator grandchild = child->second.children[j]; + cout << " - grandchild " << j+1 << ": " << grandchild->second.segment.getName() << " has joint " << grandchild->second.segment.getJoint().getName() + << " and " << grandchild->second.children.size() << " children" << endl; + + } + } + + // extract chains from tree + Chain chain1, chain2; + my_tree.getChain("l_gripper_palm_link", "r_gripper_palm_link", chain1); + my_tree.getChain("r_gripper_palm_link", "l_gripper_palm_link", chain2); + cout << "Got chain1 with " << chain1.getNrOfJoints() << " joints and " << chain1.getNrOfSegments() << " segments" << endl; + cout << "Got chain2 with " << chain2.getNrOfJoints() << " joints and " << chain2.getNrOfSegments() << " segments" << endl; + + JntArray jnt1(chain1.getNrOfJoints()); + JntArray jnt2(chain1.getNrOfJoints()); + for (int i=0; i<(int)chain1.getNrOfJoints(); i++){ + jnt1(i) = (i+1)*2; + jnt2((int)chain1.getNrOfJoints()-i-1) = -jnt1(i); + } + for (int i=0; i<(int)chain1.getNrOfJoints(); i++) + cout << "jnt 1 -- jnt 2 " << jnt1(i) << " -- " << jnt2(i) << endl; + + ChainFkSolverPos_recursive solver1(chain1); + ChainFkSolverPos_recursive solver2(chain2); + Frame f1, f2; + solver1.JntToCart(jnt1, f1); + solver2.JntToCart(jnt2, f2); + cout << "frame 1 " << f1 << endl; + cout << "frame 2 " << f2.Inverse() << endl; + + // copy tree + Tree copy = my_tree; + copy.getChain("l_gripper_palm_link", "r_gripper_palm_link", chain1); + copy.getChain("r_gripper_palm_link", "l_gripper_palm_link", chain2); + cout << "Got chain1 with " << chain1.getNrOfJoints() << " joints and " << chain1.getNrOfSegments() << " segments" << endl; + cout << "Got chain2 with " << chain2.getNrOfJoints() << " joints and " << chain2.getNrOfSegments() << " segments" << endl; + +} + diff --git a/kdl_parser/test/example_xml.cpp b/kdl_parser/test/example_xml.cpp new file mode 100644 index 0000000..75a4228 --- /dev/null +++ b/kdl_parser/test/example_xml.cpp @@ -0,0 +1,99 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#include +#include +#include "kdl_parser/xml_parser.hpp" +#include + +using namespace KDL; +using namespace std; + + +int main() +{ + Tree my_tree; + if (!treeFromFile("pr2_desc.xml", my_tree)) return -1; + + // walk through tree + SegmentMap::const_iterator root = my_tree.getRootSegment(); + cout << "Found root " << root->second.segment.getName() << " with " << root->second.children.size() << " children" << endl; + for (unsigned int i=0; isecond.children.size(); i++){ + SegmentMap::const_iterator child = root->second.children[i]; + cout << " - child " << i+1 << ": " << child->second.segment.getName() << " has joint " << child->second.segment.getJoint().getName() + << " and " << child->second.children.size() << " children" << endl; + + for (unsigned int j=0; jsecond.children.size(); j++){ + SegmentMap::const_iterator grandchild = child->second.children[j]; + cout << " - grandchild " << j+1 << ": " << grandchild->second.segment.getName() << " has joint " << grandchild->second.segment.getJoint().getName() + << " and " << grandchild->second.children.size() << " children" << endl; + + } + } + + // extract chains from tree + Chain chain1, chain2; + my_tree.getChain("l_gripper_palm_link", "r_gripper_palm_link", chain1); + my_tree.getChain("r_gripper_palm_link", "l_gripper_palm_link", chain2); + cout << "Got chain1 with " << chain1.getNrOfJoints() << " joints and " << chain1.getNrOfSegments() << " segments" << endl; + cout << "Got chain2 with " << chain2.getNrOfJoints() << " joints and " << chain2.getNrOfSegments() << " segments" << endl; + + JntArray jnt1(chain1.getNrOfJoints()); + JntArray jnt2(chain1.getNrOfJoints()); + for (int i=0; i<(int)chain1.getNrOfJoints(); i++){ + jnt1(i) = (i+1)*2; + jnt2((int)chain1.getNrOfJoints()-i-1) = -jnt1(i); + } + for (int i=0; i<(int)chain1.getNrOfJoints(); i++) + cout << "jnt 1 -- jnt 2 " << jnt1(i) << " -- " << jnt2(i) << endl; + + ChainFkSolverPos_recursive solver1(chain1); + ChainFkSolverPos_recursive solver2(chain2); + Frame f1, f2; + solver1.JntToCart(jnt1, f1); + solver2.JntToCart(jnt2, f2); + cout << "frame 1 " << f1 << endl; + cout << "frame 2 " << f2.Inverse() << endl; + + // copy tree + Tree copy = my_tree; + copy.getChain("l_gripper_palm_link", "r_gripper_palm_link", chain1); + copy.getChain("r_gripper_palm_link", "l_gripper_palm_link", chain2); + cout << "Got chain1 with " << chain1.getNrOfJoints() << " joints and " << chain1.getNrOfSegments() << " segments" << endl; + cout << "Got chain2 with " << chain2.getNrOfJoints() << " joints and " << chain2.getNrOfSegments() << " segments" << endl; + +} + diff --git a/kdl_parser/test/pr2_desc.xml b/kdl_parser/test/pr2_desc.xml new file mode 100644 index 0000000..59c6e66 --- /dev/null +++ b/kdl_parser/test/pr2_desc.xml @@ -0,0 +1,3541 @@ + + + + + + + + + + + + + + + + + + + + true + 1000.0 + + + + + + true + 1.0 + 5 + -10.0 + 1.0 + 10.0 + 1200000.0 + diagnostic + battery_state + self_test + + + + + true + 1000.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + base_collision + 100.0 + + true + 100.0 + base_bumper + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 640 + 640 + 1 + 0.0 0.0 0.0 + false + + -100 + 100 + + 0.05 + 10.0 + 0.01 + 20.0 + + 0.005 + true + 20.0 + base_scan + base_laser + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + fl_caster_l_wheel_collision + 100.0 + + true + 100.0 + fl_caster_l_wheel_bumper + + + + + + + + + 75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + fl_caster_r_wheel_collision + 100.0 + + true + 100.0 + fl_caster_r_wheel_bumper + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + fr_caster_l_wheel_collision + 100.0 + + true + 100.0 + fr_caster_l_wheel_bumper + + + + + + + + + 75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + fr_caster_r_wheel_collision + 100.0 + + true + 100.0 + fr_caster_r_wheel_bumper + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + bl_caster_l_wheel_collision + 100.0 + + true + 100.0 + bl_caster_l_wheel_bumper + + + + + + + + + 75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + bl_caster_r_wheel_collision + 100.0 + + true + 100.0 + bl_caster_r_wheel_bumper + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + br_caster_l_wheel_collision + 100.0 + + true + 100.0 + br_caster_l_wheel_bumper + + + + + + + + + 75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + br_caster_r_wheel_collision + 100.0 + + true + 100.0 + br_caster_r_wheel_bumper + + + + + + + + + -75.05 + + + + true + 100.0 + base_link + base_pose_ground_truth + 0.01 + map + 25.7 25.7 0 + 0 0 0 + + + + + + + + + + + + + + -52143.33 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + torso_lift_collision + 100.0 + + true + 100.0 + torso_lift_bumper + + + + + + + + + + + + + + + + 6.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 6.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1024 800 + 60 + 0.1 + 100 + 20.0 + + true + 20.0 + /prosilica/cam_info + /prosilica/image + /prosilica/image_rect + /prosilica/image_rect + high_def_link + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 640 480 + L8 + 90 + 0.1 + 100 + 20.0 + + true + 20.0 + stereo/left_image + stereo_l_stereo_camera_frame + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 640 480 + L8 + 90 + 0.1 + 100 + 20.0 + + true + 20.0 + stereo/right_image + stereo_r_stereo_camera_frame + + + + + + + + + true + 20.0 + stereo_l_sensor + stereo_r_sensor + stereo/raw_stereo + stereo_optical_frame + 320 + 320 + 240 + 320 + 0 + 0 + 0 + 0 + 0 + -0.09 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 6.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 640 + 640 + 1 + + 0.0 0.0 0.0 + false + + -80 + 80 + + 0.05 + 10.0 + 0.01 + 20.0 + + 0.005 + true + 20.0 + tilt_scan + laser_tilt_link + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_shoulder_pan_collision + 100.0 + + true + 100.0 + r_shoulder_pan_bumper + + + + + + + true + + + + + 63.16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_shoulder_lift_collision + 100.0 + + true + 100.0 + r_r_shoulder_lift_bumper + + + + + + + true + + + + + 61.89 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + + + + + 32.65 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_upper_arm_collision + 100.0 + + true + 100.0 + r_upper_arm_bumper + + + + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_elbow_flex_collision + 100.0 + + true + 100.0 + r_elbow_flex_bumper + + + + + + + true + + + + + -36.17 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + + + + + 90.5142857143 + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_forearm_collision + 100.0 + + true + 100.0 + r_forearm_bumper + + + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_wrist_flex_collision + 100.0 + + true + 100.0 + r_wrist_flex_bumper + + + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_wrist_roll_collision + 100.0 + + true + 100.0 + r_wrist_roll_bumper + + + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_gripper_palm_collision + 100.0 + + true + 100.0 + r_gripper_palm_bumper + + + + + + + true + + + + + true + 100.0 + r_gripper_palm_link + r_gripper_palm_pose_ground_truth + 0 0 0 + 0 0 0 + 0.0 + map + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + + + + + true + 100.0 + r_gripper_tool_frame + r_gripper_tool_frame_pose_ground_truth + 0 0 0 + 0 0 0 + 0.0 + map + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_gripper_l_finger_collision + 100.0 + + true + 100.0 + r_gripper_l_finger_bumper + + + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_gripper_r_finger_collision + 100.0 + + true + 100.0 + r_gripper_r_finger_bumper + + + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_gripper_l_finger_tip_collision + 100.0 + + true + 100.0 + r_gripper_l_finger_tip_bumper + + + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_gripper_r_finger_tip_collision + 100.0 + + true + 100.0 + r_gripper_r_finger_tip_bumper + + + + + + + true + + + + + + + + + + true + 100.0 + r_gripper_l_finger_link + r_gripper_l_finger_pose_ground_truth + 0.0 + map + + + + true + 100.0 + r_gripper_l_finger_link + r_gripper_l_finger_force_ground_truth + r_gripper_l_finger_link + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + l_shoulder_pan_collision + 100.0 + + true + 100.0 + l_shoulder_pan_bumper + + + + + + + true + + + + + 63.16 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + l_shoulder_lift_collision + 100.0 + + true + 100.0 + l_r_shoulder_lift_bumper + + + + + + + true + + + + + 61.89 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + + + + + 32.65 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + l_upper_arm_collision + 100.0 + + true + 100.0 + l_upper_arm_bumper + + + + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + l_elbow_flex_collision + 100.0 + + true + 100.0 + l_elbow_flex_bumper + + + + + + + true + + + + + -36.17 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + + + + + 90.5142857143 + + + + + + + + + + + + + + + + + + + + + + + + + + + + l_forearm_collision + 100.0 + + true + 100.0 + l_forearm_bumper + + + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + l_wrist_flex_collision + 100.0 + + true + 100.0 + l_wrist_flex_bumper + + + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + l_wrist_roll_collision + 100.0 + + true + 100.0 + l_wrist_roll_bumper + + + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + l_gripper_palm_collision + 100.0 + + true + 100.0 + l_gripper_palm_bumper + + + + + + + true + + + + + true + 100.0 + l_gripper_palm_link + l_gripper_palm_pose_ground_truth + 0 0 0 + 0 0 0 + 0.0 + map + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + + + + + true + 100.0 + l_gripper_tool_frame + l_gripper_tool_frame_pose_ground_truth + 0 0 0 + 0 0 0 + 0.0 + map + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + l_gripper_l_finger_collision + 100.0 + + true + 100.0 + l_gripper_l_finger_bumper + + + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + l_gripper_r_finger_collision + 100.0 + + true + 100.0 + l_gripper_r_finger_bumper + + + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + l_gripper_l_finger_tip_collision + 100.0 + + true + 100.0 + l_gripper_l_finger_tip_bumper + + + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + l_gripper_r_finger_tip_collision + 100.0 + + true + 100.0 + l_gripper_r_finger_tip_bumper + + + + + + + true + + + + + + + + + + true + 100.0 + l_gripper_l_finger_link + l_gripper_l_finger_pose_ground_truth + 0.0 + map + + + + true + 100.0 + l_gripper_l_finger_link + l_gripper_l_finger_force_ground_truth + l_gripper_l_finger_link + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + l_upper_arm_roll_link + r_upper_arm_roll_link + l_elbow_flex_link + r_elbow_flex_link + l_forearm_roll_link + r_forearm_roll_link + l_wrist_flex_link + r_wrist_flex_link + l_wrist_roll_link + r_wrist_roll_link + l_gripper_l_finger_link + l_gripper_r_finger_link + r_gripper_l_finger_link + r_gripper_r_finger_link + r_shoulder_pan_link + r_shoulder_lift_link + l_shoulder_pan_link + l_shoulder_lift_link + torso_lift_link + base_link + + base_link + torso_lift_link + head_pan_link + head_tilt_link + r_shoulder_pan_link + r_shoulder_lift_link + r_upper_arm_roll_link + r_upper_arm_link + r_elbow_flex_link + r_forearm_roll_link + r_forearm_link + r_wrist_flex_link + r_wrist_roll_link + r_gripper_palm_link + r_gripper_l_finger_link + r_gripper_r_finger_link + r_gripper_l_finger_tip_link + r_gripper_r_finger_tip_link + + r_forearm_link + base_link + + r_gripper_palm_link + base_link + + r_gripper_l_finger_link + base_link + + r_gripper_r_finger_link + base_link + + r_gripper_l_finger_tip_link + base_link + + r_gripper_r_finger_tip_link + base_link + + base_link + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + l_shoulder_pan_link + l_shoulder_lift_link + l_upper_arm_roll_link + l_upper_arm_link + l_elbow_flex_link + l_forearm_roll_link + l_forearm_link + l_wrist_flex_link + l_wrist_roll_link + + + + + + + + + + + + + + + + r_shoulder_pan_link + r_shoulder_lift_link + r_upper_arm_roll_link + r_upper_arm_link + r_elbow_flex_link + r_forearm_roll_link + r_forearm_link + r_wrist_flex_link + r_wrist_roll_link + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + base_link + torso_lift_link + l_shoulder_pan_link + l_shoulder_lift_link + l_upper_arm_roll_link + l_upper_arm_link + l_elbow_flex_link + l_forearm_roll_link + l_forearm_link + l_wrist_flex_link + l_wrist_roll_link + + base_link + torso_lift_link + r_shoulder_pan_link + r_shoulder_lift_link + r_upper_arm_roll_link + r_upper_arm_link + r_elbow_flex_link + r_forearm_roll_link + r_forearm_link + r_wrist_flex_link + r_wrist_roll_link + + + + + + + + + + + + + + + + l_shoulder_pan_link + l_shoulder_lift_link + l_upper_arm_roll_link + l_upper_arm_link + l_elbow_flex_link + l_forearm_roll_link + l_forearm_link + l_wrist_flex_link + l_wrist_roll_link + r_shoulder_pan_link + r_shoulder_lift_link + r_upper_arm_roll_link + r_upper_arm_link + r_elbow_flex_link + r_forearm_roll_link + r_forearm_link + r_wrist_flex_link + r_wrist_roll_link + + base_link + torso_lift_link + l_shoulder_pan_link + l_shoulder_lift_link + l_upper_arm_roll_link + l_upper_arm_link + l_elbow_flex_link + l_forearm_roll_link + l_forearm_link + l_wrist_flex_link + l_wrist_roll_link + r_shoulder_pan_link + r_shoulder_lift_link + r_upper_arm_roll_link + r_upper_arm_link + r_elbow_flex_link + r_forearm_roll_link + r_forearm_link + r_wrist_flex_link + r_wrist_roll_link + + + + + + + diff --git a/kdl_parser/test/pr2_desc_bracket.xml b/kdl_parser/test/pr2_desc_bracket.xml new file mode 100644 index 0000000..f512410 --- /dev/null +++ b/kdl_parser/test/pr2_desc_bracket.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/kdl_parser/test/pr2_desc_bracket2.xml b/kdl_parser/test/pr2_desc_bracket2.xml new file mode 100644 index 0000000..f3f2e00 --- /dev/null +++ b/kdl_parser/test/pr2_desc_bracket2.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/kdl_parser/test/pr2_desc_vector.xml b/kdl_parser/test/pr2_desc_vector.xml new file mode 100644 index 0000000..a6a37f3 --- /dev/null +++ b/kdl_parser/test/pr2_desc_vector.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/kdl_parser/test/test_kdl_parser.cpp b/kdl_parser/test/test_kdl_parser.cpp new file mode 100644 index 0000000..51b6f1f --- /dev/null +++ b/kdl_parser/test/test_kdl_parser.cpp @@ -0,0 +1,93 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#include +#include +#include +#include "kdl_parser/xml_parser.hpp" + +using namespace KDL; + +int g_argc; +char** g_argv; + +class TestParser : public testing::Test +{ +public: + Tree my_tree; + +protected: + /// constructor + TestParser() + { + } + + + /// Destructor + ~TestParser() + { + } +}; + + + + +TEST_F(TestParser, test) +{ + for (int i=1; isecond.children.size() == 1); + ASSERT_TRUE(my_tree.getSegment("base_link")->second.parent == my_tree.getRootSegment()); + SUCCEED(); +} + + + + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "test_kdl_parser"); + g_argc = argc; + g_argv = argv; + return RUN_ALL_TESTS(); +} diff --git a/kdl_parser/test/test_kdl_parser.launch b/kdl_parser/test/test_kdl_parser.launch new file mode 100644 index 0000000..b97a9ba --- /dev/null +++ b/kdl_parser/test/test_kdl_parser.launch @@ -0,0 +1,6 @@ + + + diff --git a/resource_retriever/CMakeLists.txt b/resource_retriever/CMakeLists.txt new file mode 100644 index 0000000..86b5735 --- /dev/null +++ b/resource_retriever/CMakeLists.txt @@ -0,0 +1,35 @@ +cmake_minimum_required(VERSION 2.4.6) +include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) + +# Set the build type. Options are: +# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage +# Debug : w/ debug symbols, w/o optimization +# Release : w/o debug symbols, w/ optimization +# RelWithDebInfo : w/ debug symbols, w/ optimization +# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries +#set(ROS_BUILD_TYPE RelWithDebInfo) + +rosbuild_init() + +#set the default path for built executables to the "bin" directory +set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) +#set the default path for built libraries to the "lib" directory +set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) + +#uncomment if you have defined messages +#rosbuild_genmsg() +#uncomment if you have defined services +#rosbuild_gensrv() + +include(FindCURL) + +if(NOT CURL_FOUND) +message("CURL not found! Aborting...") +fail() +endif(NOT CURL_FOUND) + +include_directories(${CURL_INCLUDE_DIRS}) +rosbuild_add_library(${PROJECT_NAME} src/retriever.cpp) +target_link_libraries(${PROJECT_NAME} ${CURL_LIBRARIES}) + +add_subdirectory(test EXCLUDE_FROM_ALL) diff --git a/resource_retriever/Makefile b/resource_retriever/Makefile new file mode 100644 index 0000000..b75b928 --- /dev/null +++ b/resource_retriever/Makefile @@ -0,0 +1 @@ +include $(shell rospack find mk)/cmake.mk \ No newline at end of file diff --git a/resource_retriever/include/resource_retriever/retriever.h b/resource_retriever/include/resource_retriever/retriever.h new file mode 100644 index 0000000..a328057 --- /dev/null +++ b/resource_retriever/include/resource_retriever/retriever.h @@ -0,0 +1,85 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef RESOURCE_RETRIEVER_RETRIEVER_H +#define RESOURCE_RETRIEVER_RETRIEVER_H + +#include +#include +#include + +typedef void CURL; + +namespace resource_retriever +{ + +class Exception : public std::runtime_error +{ +public: + Exception(const std::string& file, const std::string& error_msg) + : std::runtime_error("Error retrieving file [" + file + "]: " + error_msg) + {} +}; + +/** + * \brief A combination of a pointer to data in memory along with the data's size. + */ +struct MemoryResource +{ + MemoryResource() + : size(0) + {} + + boost::shared_array data; + uint32_t size; +}; + +/** + * \brief Retrieves files from from a url. Caches a CURL handle so multiple accesses to a single url + * will keep connections open. + */ +class Retriever +{ +public: + Retriever(); + ~Retriever(); + + /** + * \brief Get a file and store it in memory + * \param url The url to retrieve. package://package/file will be turned into the correct file:// invocation + * \return The file, loaded into memory + * \throws resource_retriever::Exception if anything goes wrong. + */ + MemoryResource get(const std::string& url); + +private: + CURL* curl_handle_; +}; + +} // namespace resource_retriever + +#endif // RESOURCE_RETRIEVER_RETRIEVER_H diff --git a/resource_retriever/mainpage.dox b/resource_retriever/mainpage.dox new file mode 100644 index 0000000..a06a758 --- /dev/null +++ b/resource_retriever/mainpage.dox @@ -0,0 +1,14 @@ +/** +\mainpage +\htmlinclude manifest.html + +\b resource_retriever is a package used for downloading files from a url. It also provides special handling of the package:// prefix, allowing things to be referenced +by path relative to a package. + + +\section codeapi Code API + + - resource_retriever::Retriever -- Use this class to download files. + + +*/ \ No newline at end of file diff --git a/resource_retriever/manifest.xml b/resource_retriever/manifest.xml new file mode 100644 index 0000000..80058d9 --- /dev/null +++ b/resource_retriever/manifest.xml @@ -0,0 +1,21 @@ + + + + A package for retrieving resources used in a urdf. Uses libcurl to support url-format files, such as http://, ftp://, etc. Translates package:// to a local file:// + + + Josh Faust (jfaust@willowgarage.com) + BSD + + http://pr.willowgarage.com/wiki/resource_retriever + + + + + + + + + + + diff --git a/resource_retriever/src/retriever.cpp b/resource_retriever/src/retriever.cpp new file mode 100644 index 0000000..b09a981 --- /dev/null +++ b/resource_retriever/src/retriever.cpp @@ -0,0 +1,147 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "resource_retriever/retriever.h" + +#include + +#include +#include + +#include + +namespace resource_retriever +{ + +class CURLStaticInit +{ +public: + CURLStaticInit() + : initialized_(false) + { + CURLcode ret = curl_global_init(CURL_GLOBAL_ALL); + if (ret != 0) + { + ROS_ERROR("Error initializing libcurl! retcode = %d", ret); + } + else + { + initialized_ = true; + } + } + + ~CURLStaticInit() + { + if (initialized_) + { + curl_global_cleanup(); + } + } + + bool initialized_; +}; +static CURLStaticInit g_curl_init; + +Retriever::Retriever() +{ + curl_handle_ = curl_easy_init(); +} + +Retriever::~Retriever() +{ + if (curl_handle_) + { + curl_easy_cleanup(curl_handle_); + } +} + +struct MemoryBuffer +{ + std::vector v; +}; + +size_t curlWriteFunc(void* buffer, size_t size, size_t nmemb, void* userp) +{ + MemoryBuffer* membuf = (MemoryBuffer*)userp; + + size_t prev_size = membuf->v.size(); + membuf->v.resize(prev_size + size * nmemb); + memcpy(&membuf->v[prev_size], buffer, size * nmemb); + + return size * nmemb; +} + +MemoryResource Retriever::get(const std::string& url) +{ + std::string mod_url = url; + if (url.find("package://") == 0) + { + mod_url.erase(0, strlen("package://")); + size_t pos = mod_url.find("/"); + if (pos == std::string::npos) + { + throw Exception(url, "Could not parse package:// format into file:// format"); + } + + std::string package = mod_url.substr(0, pos); + mod_url.erase(0, pos); + std::string package_path = ros::package::getPath(package); + + if (package_path.empty()) + { + throw Exception(url, "Package [" + package + "] does not exist"); + } + + mod_url = "file://" + package_path + mod_url; + } + + curl_easy_setopt(curl_handle_, CURLOPT_URL, mod_url.c_str()); + curl_easy_setopt(curl_handle_, CURLOPT_WRITEFUNCTION, curlWriteFunc); + + char error_buffer[CURL_ERROR_SIZE]; + curl_easy_setopt(curl_handle_, CURLOPT_ERRORBUFFER , error_buffer); + + MemoryResource res; + MemoryBuffer buf; + curl_easy_setopt(curl_handle_, CURLOPT_WRITEDATA, &buf); + + CURLcode ret = curl_easy_perform(curl_handle_); + if (ret != 0) + { + throw Exception(mod_url, error_buffer); + } + else if (!buf.v.empty()) + { + res.size = buf.v.size(); + res.data.reset(new uint8_t[res.size]); + memcpy(res.data.get(), &buf.v[0], res.size); + } + + return res; +} + +} diff --git a/resource_retriever/test/CMakeLists.txt b/resource_retriever/test/CMakeLists.txt new file mode 100644 index 0000000..7624c4c --- /dev/null +++ b/resource_retriever/test/CMakeLists.txt @@ -0,0 +1,4 @@ +set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}) + +rospack_add_gtest(test/utest test.cpp) +target_link_libraries(test/utest ${PROJECT_NAME}) diff --git a/resource_retriever/test/test.cpp b/resource_retriever/test/test.cpp new file mode 100644 index 0000000..b29f40e --- /dev/null +++ b/resource_retriever/test/test.cpp @@ -0,0 +1,140 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +#include + +#include +#include +#include + +using namespace resource_retriever; + +TEST(Retriever, getByPackage) +{ + try + { + Retriever r; + MemoryResource res = r.get("package://"ROS_PACKAGE_NAME"/test/test.txt"); + + ASSERT_EQ(res.size, 1); + ASSERT_EQ(res.data[0], 'A'); + } + catch (Exception& e) + { + FAIL(); + } +} + +TEST(Retriever, largeFile) +{ + try + { + std::string path = ros::package::getPath(ROS_PACKAGE_NAME) + "/test/large_file.dat"; + + FILE* f = fopen(path.c_str(), "w"); + + ASSERT_TRUE(f); + + for (int i = 0; i < 1024*1024*50; ++i) + { + fprintf(f, "A"); + } + fclose(f); + + Retriever r; + MemoryResource res = r.get("package://"ROS_PACKAGE_NAME"/test/large_file.dat"); + + ASSERT_EQ(res.size, 1024*1024*50); + } + catch (Exception& e) + { + FAIL(); + } +} + +TEST(Retriever, http) +{ + try + { + Retriever r; + MemoryResource res = r.get("http://pr.willowgarage.com/downloads/svnmerge.py"); + + ASSERT_GT(res.size, 0); + } + catch (Exception& e) + { + FAIL(); + } +} + +TEST(Retriever, invalidFiles) +{ + Retriever r; + + try + { + r.get("file://fail"); + FAIL(); + } + catch (Exception& e) + { + ROS_INFO("%s", e.what()); + } + + try + { + r.get("package://roscpp"); + FAIL(); + } + catch (Exception& e) + { + ROS_INFO("%s", e.what()); + } + + try + { + r.get("package://invalid_package_blah/test.xml"); + FAIL(); + } + catch (Exception& e) + { + ROS_INFO("%s", e.what()); + } +} + +int main(int argc, char **argv){ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} + diff --git a/resource_retriever/test/test.txt b/resource_retriever/test/test.txt new file mode 100644 index 0000000..8c7e5a6 --- /dev/null +++ b/resource_retriever/test/test.txt @@ -0,0 +1 @@ +A \ No newline at end of file diff --git a/robot_state_publisher/CMakeLists.txt b/robot_state_publisher/CMakeLists.txt new file mode 100644 index 0000000..71711b7 --- /dev/null +++ b/robot_state_publisher/CMakeLists.txt @@ -0,0 +1,38 @@ +cmake_minimum_required(VERSION 2.4.6) +include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) + +# Set the build type. Options are: +# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage +# Debug : w/ debug symbols, w/o optimization +# Release : w/o debug symbols, w/ optimization +# RelWithDebInfo : w/ debug symbols, w/ optimization +# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries +#set(ROS_BUILD_TYPE RelWithDebInfo) + +rosbuild_init() +rosbuild_add_boost_directories() + +#set the default path for built executables to the "bin" directory +set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) +#set the default path for built libraries to the "lib" directory +set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) + +#uncomment if you have defined messages +#genmsg() +#uncomment if you have defined services +#gensrv() + +rosbuild_add_library(${PROJECT_NAME} src/joint_state_listener.cpp src/robot_state_publisher.cpp src/treefksolverposfull_recursive.cpp) + +rosbuild_add_executable(state_publisher src/state_publisher.cpp ) +target_link_libraries(state_publisher ${PROJECT_NAME}) + +rosbuild_add_executable(test_publisher test/test_publisher.cpp ) +target_link_libraries(test_publisher ${PROJECT_NAME}) +rosbuild_add_gtest_build_flags(test_publisher) +rosbuild_declare_test(test_publisher) + +rosbuild_add_rostest(${CMAKE_CURRENT_SOURCE_DIR}/test/test_publisher.launch) + +# Download needed data file +rosbuild_download_test_data(http://pr.willowgarage.com/data/robot_state_publisher/joint_states.bag test/joint_states.bag) diff --git a/robot_state_publisher/Makefile b/robot_state_publisher/Makefile new file mode 100644 index 0000000..b75b928 --- /dev/null +++ b/robot_state_publisher/Makefile @@ -0,0 +1 @@ +include $(shell rospack find mk)/cmake.mk \ No newline at end of file diff --git a/robot_state_publisher/include/robot_state_publisher/joint_state_listener.h b/robot_state_publisher/include/robot_state_publisher/joint_state_listener.h new file mode 100644 index 0000000..ef2f4fe --- /dev/null +++ b/robot_state_publisher/include/robot_state_publisher/joint_state_listener.h @@ -0,0 +1,69 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#ifndef JOINT_STATE_LISTENER_H +#define JOINT_STATE_LISTENER_H + +#include +#include +#include +#include "robot_state_publisher/robot_state_publisher.h" + +using namespace std; +using namespace ros; +using namespace KDL; + +typedef boost::shared_ptr JointStateConstPtr; + +namespace robot_state_publisher{ + +class JointStateListener{ +public: + JointStateListener(const KDL::Tree& tree); + ~JointStateListener(); + +private: + void callbackJointState(const JointStateConstPtr& state); + + NodeHandle n_; + Rate publish_rate_; + robot_state_publisher::RobotStatePublisher state_publisher_; + Subscriber joint_state_sub_; +}; +} + + +#endif diff --git a/robot_state_publisher/include/robot_state_publisher/robot_state_publisher.h b/robot_state_publisher/include/robot_state_publisher/robot_state_publisher.h new file mode 100644 index 0000000..781082c --- /dev/null +++ b/robot_state_publisher/include/robot_state_publisher/robot_state_publisher.h @@ -0,0 +1,76 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#ifndef ROBOT_STATE_PUBLISHER_H +#define ROBOT_STATE_PUBLISHER_H + +#include +#include +#include +#include +#include "robot_state_publisher/treefksolverposfull_recursive.hpp" + +namespace robot_state_publisher{ + +class RobotStatePublisher +{ +public: + RobotStatePublisher(const KDL::Tree& tree); + ~RobotStatePublisher(){}; + + bool publishTransforms(const std::map& joint_positions, const ros::Time& time); + +private: + ros::NodeHandle n_; + ros::Publisher tf_publisher_; + KDL::Tree tree_; + boost::scoped_ptr solver_; + std::string root_; + std::string tf_prefix_; + tf::tfMessage tf_msg_; + + class empty_tree_exception: public std::exception{ + virtual const char* what() const throw(){ + return "Tree is empty";} + } empty_tree_ex; + +}; + + + +} + +#endif diff --git a/robot_state_publisher/include/robot_state_publisher/treefksolverposfull_recursive.hpp b/robot_state_publisher/include/robot_state_publisher/treefksolverposfull_recursive.hpp new file mode 100644 index 0000000..4c3e9ea --- /dev/null +++ b/robot_state_publisher/include/robot_state_publisher/treefksolverposfull_recursive.hpp @@ -0,0 +1,48 @@ +// Copyright (C) 2009 Willow Garage Inc + +// Version: 1.0 +// Author: Wim Meeussen +// Maintainer: Ruben Smits +// URL: http://www.orocos.org/kdl + +// This library is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 2.1 of the License, or (at your option) any later version. + +// This library is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// Lesser General Public License for more details. + +// You should have received a copy of the GNU Lesser General Public +// License along with this library; if not, write to the Free Software +// Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + + +#ifndef KDLTREEFKSOLVERPOSFULL_RECURSIVE_HPP +#define KDLTREEFKSOLVERPOSFULL_RECURSIVE_HPP + +#include + +namespace KDL { + +class TreeFkSolverPosFull_recursive + +{ +public: + TreeFkSolverPosFull_recursive(const Tree& _tree); + ~TreeFkSolverPosFull_recursive(); + + int JntToCart(const std::map& q_in, std::map& p_out); + +private: + void addFrameToMap(const std::map& q_in, std::map& p_out, + const Frame& previous_frame, const SegmentMap::const_iterator this_segment); + + Tree tree; + +}; +} + +#endif diff --git a/robot_state_publisher/manifest.xml b/robot_state_publisher/manifest.xml new file mode 100644 index 0000000..8da7560 --- /dev/null +++ b/robot_state_publisher/manifest.xml @@ -0,0 +1,27 @@ + + + + This package allows you to publish the state of a robot to the transform library topic. Once the state + gets published, it is available to all components in the system using the transform library. + The package takes the joint angles of the robot as input and publishes the 3D poses + of the robot links, using a kinematic tree model of the robot. The package can both be used + as a library and as a ROS node. + + + Wim Meeussen meeussen@willowgarage.com + BSD + + http://pr.willowgarage.com/wiki/robot_state_publisher + + + + + + + + + + + + + diff --git a/robot_state_publisher/src/joint_state_listener.cpp b/robot_state_publisher/src/joint_state_listener.cpp new file mode 100644 index 0000000..3ef26a1 --- /dev/null +++ b/robot_state_publisher/src/joint_state_listener.cpp @@ -0,0 +1,86 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#include +#include +#include "robot_state_publisher/robot_state_publisher.h" +#include "robot_state_publisher/joint_state_listener.h" + +using namespace std; +using namespace ros; +using namespace KDL; +using namespace robot_state_publisher; + + +JointStateListener::JointStateListener(const KDL::Tree& tree) + : publish_rate_(0.0), state_publisher_(tree) +{ + // set publish frequency + double publish_freq; + n_.param("~publish_frequency", publish_freq, 50.0); + publish_rate_ = Rate(publish_freq); + + // subscribe to mechanism state + string joint_state_topic; + n_.param("~joint_state_topic", joint_state_topic, string("joint_states")); + joint_state_sub_ = n_.subscribe(joint_state_topic, 1, &JointStateListener::callbackJointState, this);; +}; + + +JointStateListener::~JointStateListener() +{}; + + +void JointStateListener::callbackJointState(const JointStateConstPtr& state) +{ + if (state->get_name_size() == 0){ + ROS_ERROR("Robot state publisher received an empty joint state vector"); + return; + } + + if (state->get_name_size() != state->get_position_size()){ + ROS_ERROR("Robot state publisher received an invalid joint state vector"); + return; + } + + // get joint positions from state message + map joint_positions; + for (unsigned int i=0; iname.size(); i++) + joint_positions.insert(make_pair(state->name[i], state->position[i])); + state_publisher_.publishTransforms(joint_positions, state->header.stamp); + publish_rate_.sleep(); +} + diff --git a/robot_state_publisher/src/robot_state_publisher.cpp b/robot_state_publisher/src/robot_state_publisher.cpp new file mode 100644 index 0000000..bc996a1 --- /dev/null +++ b/robot_state_publisher/src/robot_state_publisher.cpp @@ -0,0 +1,106 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#include "robot_state_publisher/robot_state_publisher.h" +#include +#include + +using namespace std; +using namespace ros; +using namespace KDL; + + + +namespace robot_state_publisher{ + +RobotStatePublisher::RobotStatePublisher(const Tree& tree) + :tree_(tree) +{ + // get tf prefix + n_.param("~tf_prefix", tf_prefix_, string()); + + // build tree solver + solver_.reset(new TreeFkSolverPosFull_recursive(tree_)); + + // advertise tf message + tf_publisher_ = n_.advertise("/tf_message", 5); + tf_msg_.transforms.resize(tree.getNrOfSegments()-1); + + // get the 'real' root segment of the tree, which is the first child of "root" + SegmentMap::const_iterator root = tree.getRootSegment(); + if (root->second.children.empty()) + throw empty_tree_ex; + + root_ = (*root->second.children.begin())->first; +} + + + +bool RobotStatePublisher::publishTransforms(const map& joint_positions, const Time& time) +{ + // calculate transforms form root to every segment in tree + map link_poses; + solver_->JntToCart(joint_positions, link_poses); + + // publish the transforms to tf, converting the transforms from "root" to the 'real' root + geometry_msgs::TransformStamped trans; + map::const_iterator root = link_poses.find(root_); + if (root == link_poses.end()){ + ROS_ERROR("Did not find root of tree"); + return false; + } + + // remove root from published poses + Frame offset = root->second.Inverse(); + unsigned int i = 0; + // send transforms to tf + for (map::const_iterator f=link_poses.begin(); f!=link_poses.end(); f++){ + if (f != root){ + Frame frame = offset * f->second; + tf::Transform tf_frame; + tf::TransformKDLToTF(frame, tf_frame); + trans.header.stamp = time; + trans.header.frame_id = tf::remap(tf_prefix_, root->first); + trans.child_frame_id = tf::remap(tf_prefix_, f->first); + tf::transformTFToMsg(tf_frame, trans.transform); + tf_msg_.transforms[i++] = trans; + } + } + tf_publisher_.publish(tf_msg_); + + return true; +} +} diff --git a/robot_state_publisher/src/state_publisher.cpp b/robot_state_publisher/src/state_publisher.cpp new file mode 100644 index 0000000..6fb4143 --- /dev/null +++ b/robot_state_publisher/src/state_publisher.cpp @@ -0,0 +1,77 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#include +#include +#include +#include +#include "robot_state_publisher/joint_state_listener.h" + +using namespace std; +using namespace ros; +using namespace KDL; +using namespace robot_state_publisher; + + + +// ---------------------------------- +// ----- MAIN ----------------------- +// ---------------------------------- +int main(int argc, char** argv) +{ + // Initialize ros + ros::init(argc, argv, "robot_state_publisher"); + NodeHandle node; + + // gets the location of the robot description on the parameter server + string param_name, full_param_name; + node.param("~/robot_desc_param", param_name, string("robot_description")); + node.searchParam(param_name,full_param_name); + string robot_desc; + + // constructs a kdl tree from the robot model + node.param(full_param_name, robot_desc, string()); + Tree tree; + if (!kdl_parser::treeFromString(robot_desc, tree)){ + ROS_ERROR("Failed to extract kdl tree from xml robot description"); + return -1; + } + + JointStateListener state_publisher(tree); + + ros::spin(); + return 0; +} diff --git a/robot_state_publisher/src/treefksolverposfull_recursive.cpp b/robot_state_publisher/src/treefksolverposfull_recursive.cpp new file mode 100644 index 0000000..3381a56 --- /dev/null +++ b/robot_state_publisher/src/treefksolverposfull_recursive.cpp @@ -0,0 +1,76 @@ +// Copyright (C) 2009 Willow Garage Inc + +// Version: 1.0 +// Author: Wim Meeussen +// Maintainer: Ruben Smits +// URL: http://www.orocos.org/kdl + +// This library is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 2.1 of the License, or (at your option) any later version. + +// This library is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// Lesser General Public License for more details. + +// You should have received a copy of the GNU Lesser General Public +// License along with this library; if not, write to the Free Software +// Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + + +#include "robot_state_publisher/treefksolverposfull_recursive.hpp" +#include + +using namespace std; + +namespace KDL { + +TreeFkSolverPosFull_recursive::TreeFkSolverPosFull_recursive(const Tree& _tree): + tree(_tree) +{ +} + +TreeFkSolverPosFull_recursive::~TreeFkSolverPosFull_recursive() +{ +} + +int TreeFkSolverPosFull_recursive::JntToCart(const map& q_in, map& p_out) +{ + // clear output + p_out.clear(); + + addFrameToMap(q_in, p_out, Frame::Identity(), tree.getRootSegment()); + + return 0; +} + + + +void TreeFkSolverPosFull_recursive::addFrameToMap(const map& q_in, map& p_out, + const Frame& previous_frame, const SegmentMap::const_iterator this_segment) +{ + // get pose of this segment + Frame this_frame = previous_frame; + double jnt_p = 0; + if (this_segment->second.segment.getJoint().getType() != Joint::None){ + map::const_iterator jnt_pos = q_in.find(this_segment->second.segment.getJoint().getName()); + if (jnt_pos == q_in.end()){ + printf("Could not find value for joint %s\n", this_segment->first.c_str()); + return; + } + jnt_p = jnt_pos->second; + } + this_frame = this_frame * this_segment->second.segment.pose(jnt_p); + if (this_segment->first != tree.getRootSegment()->first) + p_out.insert(make_pair(this_segment->first, this_frame)); + + // get poses of child segments + for (vector::const_iterator child=this_segment->second.children.begin(); child !=this_segment->second.children.end(); child++) + addFrameToMap(q_in, p_out, this_frame, *child); + +} + + +} diff --git a/robot_state_publisher/test/pr2.urdf b/robot_state_publisher/test/pr2.urdf new file mode 100644 index 0000000..c19ab6c --- /dev/null +++ b/robot_state_publisher/test/pr2.urdf @@ -0,0 +1,3117 @@ + + + + + + + + + + + + + + + + + + + true + 1000.0 + + + + + + true + 1.0 + 5 + -10.0 + 1.0 + 10.0 + 1200000.0 + diagnostic + battery_state + self_test + + + + + true + 1000.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + fl_caster_l_wheel_link_geom + 100.0 + + true + 100.0 + fl_caster_l_wheel_bumper + + + + + + + + + + + + 75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + fl_caster_r_wheel_link_geom + 100.0 + + true + 100.0 + fl_caster_r_wheel_bumper + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + fr_caster_l_wheel_link_geom + 100.0 + + true + 100.0 + fr_caster_l_wheel_bumper + + + + + + + + + + + + 75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + fr_caster_r_wheel_link_geom + 100.0 + + true + 100.0 + fr_caster_r_wheel_bumper + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + bl_caster_l_wheel_link_geom + 100.0 + + true + 100.0 + bl_caster_l_wheel_bumper + + + + + + + + + + + + 75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + bl_caster_r_wheel_link_geom + 100.0 + + true + 100.0 + bl_caster_r_wheel_bumper + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + br_caster_l_wheel_link_geom + 100.0 + + true + 100.0 + br_caster_l_wheel_bumper + + + + + + + + + + + + 75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + br_caster_r_wheel_link_geom + 100.0 + + true + 100.0 + br_caster_r_wheel_bumper + + + + + + + + + + + + -75.05 + + + base_link_geom + 100.0 + + true + 100.0 + base_bumper + + + + + + + + + + + true + 100.0 + base_link + base_pose_ground_truth + 0.01 + map + 25.7 25.7 0 + 0 0 0 + + + + true + 100.0 + plug_magnet + plug_magnet_pose_ground_truth + 0.01 + map + 0 0 0 + 0 0 0 + + + + + 640 + 640 + 1 + 0.0 0.0 0.0 + false + + -100 + 100 + + 0.05 + 10.0 + 0.01 + 20.0 + + 0.005 + true + 20.0 + base_scan + base_laser + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -52143.33 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 6.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 6.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + B8G8R8 + 2448 2050 + 45 + 0.1 + 100 + 20.0 + + true + 20.0 + /prosilica/cam_info + /prosilica/image + /prosilica/image_rect + /prosilica/cam_info_service + /prosilica/poll + hight_def_optical_frame + 1224.5 + 1224.5 + 1025.5 + 2955 + 0 + 0 + 0 + 0 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 640 480 + L8 + 90 + 0.1 + 100 + 20.0 + + true + 20.0 + wide_stereo/left_image + wide_stereo_l_stereo_camera_frame + + + + + + + 640 480 + L8 + 90 + 0.1 + 100 + 20.0 + + true + 20.0 + wide_stereo/right_image + wide_stereo_r_stereo_camera_frame + + + + + + + true + 20.0 + wide_stereo_l_sensor + wide_stereo_r_sensor + wide_stereo/raw_stereo + wide_stereo_optical_frame + 320 + 320 + 240 + 320 + 0 + 0 + 0 + 0 + 0 + -0.09 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 640 480 + L8 + 90 + 0.1 + 100 + 20.0 + + true + 20.0 + narrow_stereo/left_image + narrow_stereo_l_stereo_camera_frame + + + + + + + 640 480 + L8 + 90 + 0.1 + 100 + 20.0 + + true + 20.0 + narrow_stereo/right_image + narrow_stereo_r_stereo_camera_frame + + + + + + + true + 20.0 + narrow_stereo_l_sensor + narrow_stereo_r_sensor + narrow_stereo/raw_stereo + narrow_stereo_optical_frame + 320 + 320 + 240 + 320 + 0 + 0 + 0 + 0 + 0 + -0.09 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 640 + 640 + 1 + + 0.0 0.0 0.0 + false + + -80 + 80 + + 0.05 + 10.0 + 0.01 + 20.0 + + 0.005 + true + 20.0 + tilt_scan + laser_tilt_link + + + + + + + 6.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_shoulder_pan_link_geom + 100.0 + + true + 100.0 + r_shoulder_pan_bumper + + + + + true + + + + + + r_shoulder_lift_link_geom + 100.0 + + true + 100.0 + r_r_shoulder_lift_bumper + + + + true + + + + + + + true + + + + + + + r_upper_arm_link_geom + 100.0 + + true + 100.0 + r_upper_arm_bumper + + + + true + + + + r_elbow_flex_link_geom + 100.0 + + true + 100.0 + r_elbow_flex_bumper + + + + + true + + + + + + true + + + + true + + r_forearm_link_geom + 100.0 + + true + 100.0 + r_forearm_bumper + + + + + + true + + r_wrist_flex_link_geom + 100.0 + + true + 100.0 + r_wrist_flex_bumper + + + + + + + + + true + + r_wrist_roll_link_geom + 100.0 + + true + 100.0 + r_wrist_roll_bumper + + + + + + + + + + 63.16 + + + + 61.89 + + + + 32.65 + + + + -36.17 + + + + 90.5142857143 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + + r_gripper_l_finger_link_geom + 100.0 + + true + 100.0 + r_gripper_l_finger_bumper + + + + + + + + + + + + + + + + true + + r_gripper_r_finger_link_geom + 100.0 + + true + 100.0 + r_gripper_r_finger_bumper + + + + + + + + + + + + + + + true + + + r_gripper_l_finger_tip_link_geom + 100.0 + + true + 100.0 + r_gripper_l_finger_tip_bumper + + + + + + + + + + + + + + + true + + + r_gripper_r_finger_tip_link_geom + 100.0 + + true + 100.0 + r_gripper_r_finger_tip_bumper + + + + + + + + + + + true + 100.0 + r_gripper_l_finger_link + r_gripper_l_finger_pose_ground_truth + 0.0 + map + + + + true + 100.0 + r_gripper_l_finger_link + r_gripper_l_finger_force_ground_truth + r_gripper_l_finger_link + + + + + + + + + + + + + true + + r_gripper_palm_link_geom + 100.0 + + true + 100.0 + r_gripper_palm_bumper + + + + + + true + + + + r_gripper_l_finger_tip_link + r_gripper_float_link + r_gripper_l_finger_tip_link + 0 1 0 + 0 0 0 + + + r_gripper_r_finger_tip_link + r_gripper_float_link + r_gripper_r_finger_tip_link + 0 1 0 + 0 0 0 + + + + + true + 100.0 + r_gripper_palm_link + r_gripper_palm_pose_ground_truth + 0 0 0 + 0 0 0 + 0.0 + map + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + l_shoulder_pan_link_geom + 100.0 + + true + 100.0 + l_shoulder_pan_bumper + + + + + true + + + + + + l_shoulder_lift_link_geom + 100.0 + + true + 100.0 + l_r_shoulder_lift_bumper + + + + true + + + + + + + true + + + + + + + l_upper_arm_link_geom + 100.0 + + true + 100.0 + l_upper_arm_bumper + + + + true + + + + l_elbow_flex_link_geom + 100.0 + + true + 100.0 + l_elbow_flex_bumper + + + + + true + + + + + + true + + + + true + + l_forearm_link_geom + 100.0 + + true + 100.0 + l_forearm_bumper + + + + + + true + + l_wrist_flex_link_geom + 100.0 + + true + 100.0 + l_wrist_flex_bumper + + + + + + + + + true + + l_wrist_roll_link_geom + 100.0 + + true + 100.0 + l_wrist_roll_bumper + + + + + + + + + + 63.16 + + + + 61.89 + + + + 32.65 + + + + -36.17 + + + + 90.5142857143 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + + l_gripper_l_finger_link_geom + 100.0 + + true + 100.0 + l_gripper_l_finger_bumper + + + + + + + + + + + + + + + + true + + l_gripper_r_finger_link_geom + 100.0 + + true + 100.0 + l_gripper_r_finger_bumper + + + + + + + + + + + + + + + true + + + l_gripper_l_finger_tip_link_geom + 100.0 + + true + 100.0 + l_gripper_l_finger_tip_bumper + + + + + + + + + + + + + + + true + + + l_gripper_r_finger_tip_link_geom + 100.0 + + true + 100.0 + l_gripper_r_finger_tip_bumper + + + + + + + + + + + true + 100.0 + l_gripper_l_finger_link + l_gripper_l_finger_pose_ground_truth + 0.0 + map + + + + true + 100.0 + l_gripper_l_finger_link + l_gripper_l_finger_force_ground_truth + l_gripper_l_finger_link + + + + + + + + + + + + + true + + l_gripper_palm_link_geom + 100.0 + + true + 100.0 + l_gripper_palm_bumper + + + + + + true + + + + l_gripper_l_finger_tip_link + l_gripper_float_link + l_gripper_l_finger_tip_link + 0 1 0 + 0 0 0 + + + l_gripper_r_finger_tip_link + l_gripper_float_link + l_gripper_r_finger_tip_link + 0 1 0 + 0 0 0 + + + + + true + 100.0 + l_gripper_palm_link + l_gripper_palm_pose_ground_truth + 0 0 0 + 0 0 0 + 0.0 + map + + + + true + + + + + + + + + + + + + + + diff --git a/robot_state_publisher/test/test_publisher.cpp b/robot_state_publisher/test/test_publisher.cpp new file mode 100644 index 0000000..0a2d122 --- /dev/null +++ b/robot_state_publisher/test/test_publisher.cpp @@ -0,0 +1,136 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#include +#include +#include +#include +#include +#include +#include +#include "robot_state_publisher/joint_state_listener.h" + + +using namespace ros; +using namespace tf; +using namespace robot_state_publisher; + + +int g_argc; +char** g_argv; + +#define EPS 0.01 + +class TestPublisher : public testing::Test +{ +public: + JointStateListener* publisher; + +protected: + /// constructor + TestPublisher() + { + // constructs a robot model from the xml file + urdf::Model robot_model; + if (g_argc == 2){ + if (!robot_model.initFile(g_argv[1])) + ROS_ERROR("Failed to construct robot model from xml string"); + } + else + ROS_ERROR("No robot model as argument given"); + + // constructs a kdl tree from the robot model + Tree tree; + if (!kdl_parser::treeFromRobotModel(robot_model, tree)) + ROS_ERROR("Failed to extract kdl tree from robot model"); + + publisher = new JointStateListener(tree); + } + + /// Destructor + ~TestPublisher() + { + delete publisher; + } +}; + + + + + +TEST_F(TestPublisher, test) +{ + ROS_INFO("Creating tf listener"); + TransformListener tf; + + ROS_INFO("Waiting for bag to complete"); + Duration(15.0).sleep(); + + ASSERT_TRUE(tf.canTransform("base_link", "torso_lift_link", Time())); + ASSERT_TRUE(tf.canTransform("base_link", "r_gripper_palm_link", Time())); + ASSERT_TRUE(tf.canTransform("base_link", "r_gripper_palm_link", Time())); + ASSERT_TRUE(tf.canTransform("l_gripper_palm_link", "r_gripper_palm_link", Time())); + ASSERT_TRUE(tf.canTransform("l_gripper_palm_link", "fl_caster_r_wheel_link", Time())); + ASSERT_FALSE(tf.canTransform("base_link", "wim_link", Time())); + + tf::Stamped t; + tf.lookupTransform("base_link", "r_gripper_palm_link",Time(), t ); + EXPECT_NEAR(t.getOrigin().x(), 0.769198, EPS); + EXPECT_NEAR(t.getOrigin().y(), -0.188800, EPS); + EXPECT_NEAR(t.getOrigin().z(), 0.764914, EPS); + + tf.lookupTransform("l_gripper_palm_link", "r_gripper_palm_link",Time(), t ); + EXPECT_NEAR(t.getOrigin().x(), 0.000384222, EPS); + EXPECT_NEAR(t.getOrigin().y(), -0.376021, EPS); + EXPECT_NEAR(t.getOrigin().z(), -1.0858e-05, EPS); + + SUCCEED(); +} + + + + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "test_robot_state_publisher"); + ros::NodeHandle node; + boost::thread ros_thread(boost::bind(&ros::spin)); + + g_argc = argc; + g_argv = argv; + return RUN_ALL_TESTS(); +} diff --git a/robot_state_publisher/test/test_publisher.launch b/robot_state_publisher/test/test_publisher.launch new file mode 100644 index 0000000..2041edc --- /dev/null +++ b/robot_state_publisher/test/test_publisher.launch @@ -0,0 +1,5 @@ + + + + + diff --git a/stack.xml b/stack.xml new file mode 100644 index 0000000..8aa3a36 --- /dev/null +++ b/stack.xml @@ -0,0 +1,15 @@ + + + These are robot_model-related packages. + + John Hsu johnhsu@willowgarage.com + BSD + + http://ros.org/wiki/robot_model + + + + + + + diff --git a/urdf/CMakeLists.txt b/urdf/CMakeLists.txt new file mode 100644 index 0000000..fa9ab91 --- /dev/null +++ b/urdf/CMakeLists.txt @@ -0,0 +1,36 @@ +cmake_minimum_required(VERSION 2.4.6) +include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) + +# Set the build type. Options are: +# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage +# Debug : w/ debug symbols, w/o optimization +# Release : w/o debug symbols, w/ optimization +# RelWithDebInfo : w/ debug symbols, w/ optimization +# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries +set(ROS_BUILD_TYPE Debug) + +rosbuild_init() + +#set the default path for built executables to the "bin" directory +set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) +#set the default path for built libraries to the "lib" directory +set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) + +#uncomment if you have defined messages +#genmsg() + +rosbuild_gensrv() + +#common commands for building c++ executables and libraries +rosbuild_add_library(${PROJECT_NAME} src/link.cpp src/joint.cpp src/model.cpp) +#target_link_libraries(${PROJECT_NAME} another_library) +rosbuild_add_boost_directories() +#rosbuild_link_boost(${PROJECT_NAME} thread) + +rosbuild_add_executable(parse_test test/parse_test.cpp) +target_link_libraries(parse_test ${PROJECT_NAME}) + +rosbuild_add_executable(test_parser EXCLUDE_FROM_ALL test/test_robot_model_parser.cpp) +rosbuild_add_gtest_build_flags(test_parser) +target_link_libraries(test_parser ${PROJECT_NAME}) +rosbuild_add_rostest(${PROJECT_SOURCE_DIR}/test/test_robot_model_parser.launch) diff --git a/urdf/Makefile b/urdf/Makefile new file mode 100644 index 0000000..b75b928 --- /dev/null +++ b/urdf/Makefile @@ -0,0 +1 @@ +include $(shell rospack find mk)/cmake.mk \ No newline at end of file diff --git a/urdf/include/urdf/color.h b/urdf/include/urdf/color.h new file mode 100644 index 0000000..e3a7b3e --- /dev/null +++ b/urdf/include/urdf/color.h @@ -0,0 +1,96 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Josh Faust */ + +#ifndef URDF_COLOR_H +#define URDF_COLOR_H + +#include +#include +#include +#include +#include + +namespace urdf +{ + +class Color +{ +public: + Color() {this->clear();}; + float r; + float g; + float b; + float a; + + void clear() + { + r = g = b = 0.0f; + a = 1.0f; + } + bool init(const std::string &vector_str) + { + this->clear(); + std::vector pieces; + std::vector rgba; + boost::split( pieces, vector_str, boost::is_any_of(" ")); + for (unsigned int i = 0; i < pieces.size(); ++i) + { + if (!pieces[i].empty()) + { + ///@todo: do better atof check if string is a number + rgba.push_back(atof(pieces[i].c_str())); + } + } + + if (rgba.size() != 4) + { + ROS_ERROR("Color contains %i elements instead of 4 elements", (int)rgba.size()); + return false; + } + + this->r = rgba[0]; + this->g = rgba[1]; + this->b = rgba[2]; + this->a = rgba[3]; + + return true; + }; +}; + +} + +#endif + diff --git a/urdf/include/urdf/joint.h b/urdf/include/urdf/joint.h new file mode 100644 index 0000000..3e08308 --- /dev/null +++ b/urdf/include/urdf/joint.h @@ -0,0 +1,204 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#ifndef URDF_JOINT_H +#define URDF_JOINT_H + +#include +#include +#include +#include + +#include "pose.h" + +namespace urdf{ + +class Link; + +class JointDynamics +{ +public: + JointDynamics() { this->clear(); }; + double damping; + double friction; + + void clear() + { + damping = 0; + friction = 0; + }; + bool initXml(TiXmlElement* config); +}; + +class JointLimits +{ +public: + JointLimits() { this->clear(); }; + double lower; + double upper; + double effort; + double velocity; + + void clear() + { + lower = 0; + upper = 0; + effort = 0; + velocity = 0; + }; + bool initXml(TiXmlElement* config); +}; + +class JointSafety +{ +public: + JointSafety() { this->clear(); }; + double soft_upper_limit; + double soft_lower_limit; + double k_position; + double k_velocity; + + void clear() + { + soft_upper_limit = 0; + soft_lower_limit = 0; + k_position = 0; + k_velocity = 0; + }; + bool initXml(TiXmlElement* config); +}; + + +class JointCalibration +{ +public: + JointCalibration() { this->clear(); }; + double reference_position; + + void clear() + { + reference_position = 0; + }; + bool initXml(TiXmlElement* config); +}; + +class JointMimic +{ +public: + JointMimic() { this->clear(); }; + double offset; + double multiplier; + std::string joint_name; + + void clear() + { + offset = 0; + multiplier = 0; + joint_name.clear(); + }; + bool initXml(TiXmlElement* config); +}; + + +class Joint +{ +public: + + Joint() { this->clear(); }; + + std::string name; + enum + { + UNKNOWN, REVOLUTE, CONTINUOUS, PRISMATIC, FLOATING, PLANAR, FIXED + } type; + + /// \brief type_ meaning of axis_ + /// ------------------------------------------------------ + /// UNKNOWN unknown type + /// REVOLUTE rotation axis + /// PRISMATIC translation axis + /// FLOATING N/A + /// PLANAR plane normal axis + /// FIXED N/A + Vector3 axis; + + /// child Link element + /// child link frame is the same as the Joint frame + std::string child_link_name; + + /// parent Link element + /// origin specifies the transform from Parent Link to Joint Frame + std::string parent_link_name; + /// transform from Parent Link frame to Joint frame + Pose parent_to_joint_origin_transform; + + /// @todo: should use weak pointer here + //boost::shared_ptr link; + //boost::shared_ptr parent_link; + + /// Joint Dynamics + boost::shared_ptr dynamics; + + /// Joint Limits + boost::shared_ptr limits; + + /// Unsupported Hidden Feature + boost::shared_ptr safety; + + /// Unsupported Hidden Feature + boost::shared_ptr calibration; + + /// Option to Mimic another Joint + boost::shared_ptr mimic; + + bool initXml(TiXmlElement* xml); + void clear() + { + this->axis.clear(); + this->child_link_name.clear(); + this->parent_link_name.clear(); + this->parent_to_joint_origin_transform.clear(); + this->dynamics.reset(); + this->limits.reset(); + this->safety.reset(); + this->calibration.reset(); + this->type = UNKNOWN; + }; +}; + +} + +#endif diff --git a/urdf/include/urdf/link.h b/urdf/include/urdf/link.h new file mode 100644 index 0000000..b5722fa --- /dev/null +++ b/urdf/include/urdf/link.h @@ -0,0 +1,238 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#ifndef URDF_LINK_H +#define URDF_LINK_H + +#include +#include +#include +#include + +#include "joint.h" +#include "color.h" + +namespace urdf{ + +class Geometry +{ +public: + enum {SPHERE, BOX, CYLINDER, MESH} type; + + virtual bool initXml(TiXmlElement *) = 0; + +}; + +class Sphere : public Geometry +{ +public: + Sphere() { this->clear(); }; + double radius; + + void clear() + { + radius = 0; + }; + bool initXml(TiXmlElement *); +}; + +class Box : public Geometry +{ +public: + Box() { this->clear(); }; + Vector3 dim; + + void clear() + { + dim.clear(); + }; + bool initXml(TiXmlElement *); +}; + +class Cylinder : public Geometry +{ +public: + Cylinder() { this->clear(); }; + double length; + double radius; + + void clear() + { + length = 0; + radius = 0; + }; + bool initXml(TiXmlElement *); +}; + +class Mesh : public Geometry +{ +public: + Mesh() { this->clear(); }; + std::string filename; + Vector3 scale; + + void clear() + { + filename.clear(); + // default scale + scale.x = 1; + scale.y = 1; + scale.z = 1; + }; + bool initXml(TiXmlElement *); +}; + +class Material +{ +public: + Material() { this->clear(); }; + std::string name; + std::string texture_filename; + Color color; + + void clear() + { + color.clear(); + texture_filename.clear(); + name.clear(); + }; + bool initXml(TiXmlElement* config); +}; + +class Inertial +{ +public: + Inertial() { this->clear(); }; + Pose origin; + double mass; + double ixx,ixy,ixz,iyy,iyz,izz; + + void clear() + { + origin.clear(); + mass = 0; + ixx = ixy = ixz = iyy = iyz = izz = 0; + }; + bool initXml(TiXmlElement* config); +}; + +class Visual +{ +public: + Visual() { this->clear(); }; + Pose origin; + boost::shared_ptr geometry; + + std::string material_name; + boost::shared_ptr material; + + void clear() + { + origin.clear(); + material_name.clear(); + material.reset(); + geometry.reset(); + }; + bool initXml(TiXmlElement* config); +}; + +class Collision +{ +public: + Collision() { this->clear(); }; + Pose origin; + boost::shared_ptr geometry; + + void clear() + { + origin.clear(); + geometry.reset(); + }; + bool initXml(TiXmlElement* config); +}; + + +class Link +{ +public: + Link() { this->clear(); }; + + std::string name; + + /// inertial element + boost::shared_ptr inertial; + + /// visual element + boost::shared_ptr visual; + + /// collision element + boost::shared_ptr collision; + + /// Parent Joint element + /// explicitly stating "parent" because we want directional-ness for tree structure + /// every link can have one parent + boost::shared_ptr parent_joint; + /// Get Parent Link throught the Parent Joint + boost::shared_ptr parent_link; + + std::vector > child_joints; + std::vector > child_links; + + bool initXml(TiXmlElement* config); + void setParent(boost::shared_ptr parent); + + void clear() + { + this->name.clear(); + this->inertial.reset(); + this->visual.reset(); + this->collision.reset(); + this->parent_joint.reset(); + this->parent_link.reset(); + this->child_joints.clear(); + this->child_links.clear(); + }; + void setParentJoint(boost::shared_ptr child); + void addChild(boost::shared_ptr child); + void addChildJoint(boost::shared_ptr child); +}; + + + + +} + +#endif diff --git a/urdf/include/urdf/model.h b/urdf/include/urdf/model.h new file mode 100644 index 0000000..8a3fe37 --- /dev/null +++ b/urdf/include/urdf/model.h @@ -0,0 +1,111 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#ifndef ROBOT_MODEL_PARSER_H +#define ROBOT_MODEL_PARSER_H + +#include +#include +#include +#include +#include "link.h" + + +namespace urdf{ + + +class Model +{ +public: + Model(); + + bool initXml(TiXmlElement *xml); + bool initXml(TiXmlDocument *xml); + bool initFile(const std::string& filename); + bool initString(const std::string& xmlstring); + + boost::shared_ptr getRoot(void) const{return this->root_link_;}; + boost::shared_ptr getLink(const std::string& name) const; + boost::shared_ptr getJoint(const std::string& name) const; + const std::string& getName() const {return name_;}; + + void getLinks(std::vector >& links) const; + + /// Some accessor functions + boost::shared_ptr getParentLink(const std::string& name) const; + boost::shared_ptr getParentJoint(const std::string& name) const; + boost::shared_ptr getChildLink(const std::string& name) const; + boost::shared_ptr getChildJoint(const std::string& name) const; + + /// Every Robot Description File can be described as a + /// list of Links and Joints + /// The connection between links(nodes) and joints(edges) + /// should define a tree (i.e. 1 parent link, 0+ children links) + std::map > links_; + std::map > joints_; + std::map > materials_; + +private: + void clear(); + + std::string name_; + + /// non-const getLink() + void getLink(const std::string& name,boost::shared_ptr &link) const; + + /// non-const getMaterial() + boost::shared_ptr getMaterial(const std::string& name) const; + + /// in initXml(), onece all links are loaded, + /// it's time to build a tree + bool initTree(std::map &parent_link_tree); + + /// in initXml(), onece tree is built, + /// it's time to find the root Link + bool initRoot(std::map &parent_link_tree); + + + /// Model is restricted to a tree for now, which means there exists one root link + /// typically, root link is the world(inertial). Where world is a special link + /// or is the root_link_ the link attached to the world by PLANAR/FLOATING joint? + /// hmm... + boost::shared_ptr root_link_; + +}; + +} + +#endif diff --git a/urdf/include/urdf/pose.h b/urdf/include/urdf/pose.h new file mode 100644 index 0000000..0b76258 --- /dev/null +++ b/urdf/include/urdf/pose.h @@ -0,0 +1,232 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#ifndef URDF_POSE_H +#define URDF_POSE_H + +#include +#include +#include +#include +#include + +namespace urdf{ + +class Vector3 +{ +public: + Vector3(double _x,double _y, double _z) {this->x=_x;this->y=_y;this->z=_z;}; + Vector3() {this->clear();}; + double x; + double y; + double z; + + void clear() {this->x=this->y=this->z=0.0;}; + bool init(const std::string &vector_str) + { + this->clear(); + std::vector pieces; + std::vector xyz; + boost::split( pieces, vector_str, boost::is_any_of(" ")); + for (unsigned int i = 0; i < pieces.size(); ++i){ + if (pieces[i] != ""){ + ///@todo: do better atof check if string is a number + xyz.push_back(atof(pieces[i].c_str())); + } + } + + if (xyz.size() != 3) { + ROS_ERROR("Vector contains %i elements instead of 3 elements", (int)xyz.size()); + return false; + } + + this->x = xyz[0]; + this->y = xyz[1]; + this->z = xyz[2]; + + return true; + }; +}; + +class Rotation +{ +public: + Rotation(double _x,double _y, double _z, double _w) {this->x=_x;this->y=_y;this->z=_z;this->w=_w;}; + Rotation() {this->clear();}; + void getQuaternion(double &quat_x,double &quat_y,double &quat_z, double &quat_w) + { + quat_x = this->x; + quat_y = this->y; + quat_z = this->z; + quat_w = this->w; + }; + void getRPY(double &roll,double &pitch,double &yaw) + { + double sqw; + double sqx; + double sqy; + double sqz; + + sqx = this->x * this->x; + sqy = this->y * this->y; + sqz = this->z * this->z; + sqw = this->w * this->w; + + roll = atan2(2 * (this->y*this->z + this->w*this->x), sqw - sqx - sqy + sqz); + pitch = asin(-2 * (this->x*this->z - this->w*this->y)); + yaw = atan2(2 * (this->x*this->y + this->w*this->z), sqw + sqx - sqy - sqz); + + }; + void setFromQuaternion(double quat_x,double quat_y,double quat_z,double quat_w) + { + this->x = quat_x; + this->y = quat_y; + this->z = quat_z; + this->w = quat_w; + this->normalize(); + }; + void setFromRPY(double roll, double pitch, double yaw) + { + double phi, the, psi; + + phi = roll / 2.0; + the = pitch / 2.0; + psi = yaw / 2.0; + + this->x = sin(phi) * cos(the) * cos(psi) - cos(phi) * sin(the) * sin(psi); + this->y = cos(phi) * sin(the) * cos(psi) + sin(phi) * cos(the) * sin(psi); + this->z = cos(phi) * cos(the) * sin(psi) - sin(phi) * sin(the) * cos(psi); + this->w = cos(phi) * cos(the) * cos(psi) + sin(phi) * sin(the) * sin(psi); + + this->normalize(); + }; + + double x,y,z,w; + + bool init(const std::string &rotation_str) + { + this->clear(); + + Vector3 rpy; + + if (!rpy.init(rotation_str)) + return false; + else + { + this->setFromRPY(rpy.x,rpy.y,rpy.z); + return true; + } + + }; + + void clear() { this->x=this->y=this->z=0.0;this->w=1.0; } + + void normalize() + { + double s = sqrt(this->x * this->x + + this->y * this->y + + this->z * this->z + + this->w * this->w); + this->x /= s; + this->y /= s; + this->z /= s; + this->w /= s; + }; +}; + +class Pose +{ +public: + Pose() { this->clear(); }; + + Vector3 position; + Rotation rotation; + + void clear() + { + this->position.clear(); + this->rotation.clear(); + }; + bool initXml(TiXmlElement* xml) + { + this->clear(); + if (!xml) + { + ROS_DEBUG("parsing pose: xml empty"); + return false; + } + else + { + const char* xyz_str = xml->Attribute("xyz"); + if (xyz_str == NULL) + { + ROS_DEBUG("parsing pose: no xyz, using default values."); + return true; + } + else + { + if (!this->position.init(xyz_str)) + { + ROS_ERROR("malformed xyz"); + this->position.clear(); + return false; + } + } + + const char* rpy_str = xml->Attribute("rpy"); + if (rpy_str == NULL) + { + ROS_DEBUG("parsing pose: no rpy, using default values."); + return true; + } + else + { + if (!this->rotation.init(rpy_str)) + { + ROS_ERROR("malformed rpy"); + return false; + this->rotation.clear(); + } + } + + return true; + } + }; +}; + +} + +#endif diff --git a/urdf/mainpage.dox b/urdf/mainpage.dox new file mode 100644 index 0000000..6b3d3b1 --- /dev/null +++ b/urdf/mainpage.dox @@ -0,0 +1,209 @@ +/** +\mainpage +\htmlinclude manifest.html + +\b robot_model is ... + + + +\li RobotModel is a class containing robot model data structure. + +\li Below is an example Robot Description Describing a Parent Link "P", a Child Link "C", and a Joint "J" + +\li OLD URDF: + @verbatim + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @endverbatim +\li NEW URDF XML that corresponds to the current RobotModel data structure: + @verbatim + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @endverbatim + + + +\section codeapi Code API + + + +\section rosapi ROS API + + + + + + + + +*/ diff --git a/urdf/manifest.xml b/urdf/manifest.xml new file mode 100644 index 0000000..09294b4 --- /dev/null +++ b/urdf/manifest.xml @@ -0,0 +1,19 @@ + + + This package containt a parser for the Xml Robot Description Format (URDF). + + Wim Meeussen, John Hsu + BSD + + http://pr.willowgarage.com/wiki/urdf + + + + + + + + + + + diff --git a/urdf/src/joint.cpp b/urdf/src/joint.cpp new file mode 100644 index 0000000..3f1cfce --- /dev/null +++ b/urdf/src/joint.cpp @@ -0,0 +1,387 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: John Hsu */ + +#include +#include + +namespace urdf{ + +bool JointDynamics::initXml(TiXmlElement* config) +{ + this->clear(); + + // Get joint damping + const char* damping_str = config->Attribute("damping"); + if (damping_str == NULL) + ROS_DEBUG("joint dynamics: no damping"); + else + this->damping = atof(damping_str); + + // Get joint friction + const char* friction_str = config->Attribute("friction"); + if (friction_str == NULL) + ROS_DEBUG("joint dynamics: no friction"); + else + this->friction = atof(friction_str); + + if (damping_str == NULL && friction_str == NULL) + { + ROS_ERROR("joint dynamics element specified with no damping and no friction"); + return false; + } + else{ + ROS_DEBUG("joint dynamics: damping %f and friction %f", damping, friction); + return true; + } +} + +bool JointLimits::initXml(TiXmlElement* config) +{ + this->clear(); + + // Get lower joint limit + const char* lower_str = config->Attribute("lower"); + if (lower_str == NULL) + ROS_DEBUG("joint limit: no lower"); + else + this->lower = atof(lower_str); + + // Get upper joint limit + const char* upper_str = config->Attribute("upper"); + if (upper_str == NULL) + ROS_DEBUG("joint limit: no upper"); + else + this->upper = atof(upper_str); + + // Get joint effort limit + const char* effort_str = config->Attribute("effort"); + if (effort_str == NULL) + ROS_DEBUG("joint limit: no effort"); + else + this->effort = atof(effort_str); + + // Get joint velocity limit + const char* velocity_str = config->Attribute("velocity"); + if (velocity_str == NULL) + ROS_DEBUG("joint limit: no velocity"); + else + this->velocity = atof(velocity_str); + + if (lower_str == NULL && upper_str == NULL && effort_str == NULL && velocity_str == NULL) + { + ROS_ERROR("joint limit element specified with no readable attributes"); + return false; + } + else + return true; +} + +bool JointSafety::initXml(TiXmlElement* config) +{ + this->clear(); + + // Get soft_lower_limit joint limit + const char* soft_lower_limit_str = config->Attribute("soft_lower_limit"); + if (soft_lower_limit_str == NULL) + { + ROS_DEBUG("joint safety: no soft_lower_limit, using default value"); + this->soft_lower_limit = 0; + } + else + this->soft_lower_limit = atof(soft_lower_limit_str); + + // Get soft_upper_limit joint limit + const char* soft_upper_limit_str = config->Attribute("soft_upper_limit"); + if (soft_upper_limit_str == NULL) + { + ROS_DEBUG("joint safety: no soft_upper_limit, using default value"); + this->soft_upper_limit = 0; + } + else + this->soft_upper_limit = atof(soft_upper_limit_str); + + // Get k_position_ safety "position" gain - not exactly position gain + const char* k_position_str = config->Attribute("k_position"); + if (k_position_str == NULL) + { + ROS_DEBUG("joint safety: no k_position, using default value"); + this->k_position = 0; + } + else + this->k_position = atof(k_position_str); + // Get k_velocity_ safety velocity gain + const char* k_velocity_str = config->Attribute("k_velocity"); + if (k_velocity_str == NULL) + { + ROS_DEBUG("joint safety: no k_velocity, using default value"); + this->k_velocity = 0; + } + else + this->k_velocity = atof(k_velocity_str); + + return true; +} + +bool JointCalibration::initXml(TiXmlElement* config) +{ + this->clear(); + + // Get reference_position + const char* reference_position_str = config->Attribute("reference_position"); + if (reference_position_str == NULL) + { + ROS_DEBUG("joint calibration: no reference_position, using default value"); + this->reference_position = 0; + } + else + this->reference_position = atof(reference_position_str); + + return true; +} + +bool JointMimic::initXml(TiXmlElement* config) +{ + this->clear(); + + // Get name of joint to mimic + const char* joint_name_str = config->Attribute("joint"); + if (joint_name_str == NULL) + { + ROS_WARN("joint mimic: no mimic joint specified"); + return false; + } + else + this->joint_name = joint_name_str; + + // Get mimic multiplier + const char* multiplier_str = config->Attribute("multiplier"); + if (multiplier_str == NULL) + { + ROS_DEBUG("joint mimic: no multiplier, using default value of 1"); + this->multiplier = 1; + } + else + this->multiplier = atof(multiplier_str); + + // Get mimic offset + const char* offset_str = config->Attribute("offset"); + if (offset_str == NULL) + { + ROS_DEBUG("joint mimic: no offset, using default value of 0"); + this->offset = 0; + } + else + this->offset = atof(offset_str); + + return true; +} + +bool Joint::initXml(TiXmlElement* config) +{ + this->clear(); + + // Get Joint Name + const char *name = config->Attribute("name"); + if (!name) + { + ROS_ERROR("unnamed joint found"); + return false; + } + this->name = name; + + // Get transform from Parent Link to Joint Frame + TiXmlElement *origin_xml = config->FirstChildElement("origin"); + if (!origin_xml) + { + ROS_DEBUG("Joint '%s' missing origin tag under parent describing transform from Parent Link to Joint Frame, (using Identity transform).", this->name.c_str()); + this->parent_to_joint_origin_transform.clear(); + } + else + { + if (!this->parent_to_joint_origin_transform.initXml(origin_xml)) + { + ROS_ERROR("Malformed parent origin element for joint '%s'", this->name.c_str()); + this->parent_to_joint_origin_transform.clear(); + return false; + } + } + + // Get Parent Link + TiXmlElement *parent_xml = config->FirstChildElement("parent"); + if (parent_xml) + { + const char *pname = parent_xml->Attribute("link"); + if (!pname) + ROS_INFO("no parent link name specified for Joint link '%s'. this might be the root?", this->name.c_str()); + else + { + this->parent_link_name = std::string(pname); + + } + } + + // Get Child Link + TiXmlElement *child_xml = config->FirstChildElement("child"); + if (child_xml) + { + const char *pname = child_xml->Attribute("link"); + if (!pname) + ROS_INFO("no child link name specified for Joint link '%s'.", this->name.c_str()); + else + { + this->child_link_name = std::string(pname); + + } + } + + // Get Joint type + const char* type_char = config->Attribute("type"); + if (!type_char) + { + ROS_ERROR("joint '%s' has no type, check to see if it's a reference.", this->name.c_str()); + return false; + } + std::string type_str = type_char; + if (type_str == "planar") + type = PLANAR; + else if (type_str == "floating") + type = FLOATING; + else if (type_str == "revolute") + type = REVOLUTE; + else if (type_str == "continuous") + type = CONTINUOUS; + else if (type_str == "prismatic") + type = PRISMATIC; + else if (type_str == "fixed") + type = FIXED; + else + { + ROS_ERROR("Joint '%s' has no known type '%s'", this->name.c_str(), type_str.c_str()); + return false; + } + + // Get Joint Axis + if (this->type != FLOATING) + { + // axis + TiXmlElement *axis_xml = config->FirstChildElement("axis"); + if (axis_xml) + { + if (!axis_xml->Attribute("xyz")) + ROS_INFO("no xyz attribute for axis element for Joint link '%s', using default values", this->name.c_str()); + else + { + if (!this->axis.init(axis_xml->Attribute("xyz"))) + { + if (this->type == PLANAR) + ROS_DEBUG("PLANAR Joint '%s' will require an axis tag in the future which indicates the surface normal of the plane.", this->name.c_str()); + else + { + ROS_ERROR("Malformed axis element for joint '%s'", this->name.c_str()); + this->axis.clear(); + return false; + } + } + } + } + } + + // Get limit + TiXmlElement *limit_xml = config->FirstChildElement("limit"); + if (limit_xml) + { + limits.reset(new JointLimits); + if (!limits->initXml(limit_xml)) + { + ROS_ERROR("Could not parse limit element for joint '%s'", this->name.c_str()); + limits.reset(); + } + } + + // Get safety + TiXmlElement *safety_xml = config->FirstChildElement("safety_controller"); + if (safety_xml) + { + safety.reset(new JointSafety); + if (!safety->initXml(safety_xml)) + { + ROS_ERROR("Could not parse safety element for joint '%s'", this->name.c_str()); + safety.reset(); + } + } + + // Get calibration + TiXmlElement *calibration_xml = config->FirstChildElement("calibration"); + if (calibration_xml) + { + calibration.reset(new JointCalibration); + if (!calibration->initXml(calibration_xml)) + { + ROS_ERROR("Could not parse calibration element for joint '%s'", this->name.c_str()); + calibration.reset(); + } + } + + // Get Joint Mimic + TiXmlElement *mimic_xml = config->FirstChildElement("mimic"); + if (mimic_xml) + { + mimic.reset(new JointMimic); + if (!mimic->initXml(mimic_xml)) + { + ROS_WARN("Could not parse mimic element for joint '%s'", this->name.c_str()); + mimic.reset(); + } + } + + // Get Dynamics + TiXmlElement *prop_xml = config->FirstChildElement("dynamics"); + if (prop_xml) + { + dynamics.reset(new JointDynamics); + if (!dynamics->initXml(prop_xml)) + { + ROS_ERROR("Could not parse joint_dynamics element for joint '%s'", this->name.c_str()); + dynamics.reset(); + } + } + + return true; +} + + + +} diff --git a/urdf/src/link.cpp b/urdf/src/link.cpp new file mode 100644 index 0000000..a979a67 --- /dev/null +++ b/urdf/src/link.cpp @@ -0,0 +1,434 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + + +#include "urdf/link.h" +#include + +namespace urdf{ + +boost::shared_ptr parseGeometry(TiXmlElement *g) +{ + boost::shared_ptr geom; + if (!g) return geom; + + TiXmlElement *shape = g->FirstChildElement(); + if (!shape) + { + ROS_ERROR("Geometry tag contains no child element."); + return geom; + } + + std::string type_name = shape->ValueStr(); + if (type_name == "sphere") + geom.reset(new Sphere); + else if (type_name == "box") + geom.reset(new Box); + else if (type_name == "cylinder") + geom.reset(new Cylinder); + else if (type_name == "mesh") + geom.reset(new Mesh); + else + { + ROS_ERROR("Unknown geometry type '%s'", type_name.c_str()); + return geom; + } + + if (!geom->initXml(shape)) + return geom; + + return geom; +} + +bool Material::initXml(TiXmlElement *config) +{ + bool has_rgb = false; + bool has_filename = false; + + this->clear(); + + if (!config->Attribute("name")) + { + ROS_ERROR("Material must contain a name attribute"); + return false; + } + + this->name = config->Attribute("name"); + + // texture + TiXmlElement *t = config->FirstChildElement("texture"); + if (t) + { + if (t->Attribute("filename")) + { + this->texture_filename = t->Attribute("filename"); + has_filename = true; + } + else + { + ROS_ERROR("texture has no filename for Material %s",this->name.c_str()); + } + } + + // color + TiXmlElement *c = config->FirstChildElement("color"); + if (c) + { + if (c->Attribute("rgba")) + { + if (!this->color.init(c->Attribute("rgba"))) + { + ROS_ERROR("Material %s has malformed color rgba values.",this->name.c_str()); + this->color.clear(); + return false; + } + else + has_rgb = true; + } + else + { + ROS_ERROR("Material %s color has no rgba",this->name.c_str()); + } + } + + return (has_rgb || has_filename); +} + +bool Inertial::initXml(TiXmlElement *config) +{ + this->clear(); + + // Origin + TiXmlElement *o = config->FirstChildElement("origin"); + if (!o) + { + ROS_INFO("Origin tag not present for inertial element, using default (Identity)"); + this->origin.clear(); + } + else + { + if (!this->origin.initXml(o)) + { + ROS_ERROR("Inertial has a malformed origin tag"); + this->origin.clear(); + return false; + } + } + + TiXmlElement *mass_xml = config->FirstChildElement("mass"); + if (!mass_xml) + { + ROS_ERROR("Inertial element must have mass element"); + return false; + } + if (!mass_xml->Attribute("value")) + { + ROS_ERROR("Inertial: mass element must have value attributes"); + return false; + } + mass = atof(mass_xml->Attribute("value")); + + TiXmlElement *inertia_xml = config->FirstChildElement("inertia"); + if (!inertia_xml) + { + ROS_ERROR("Inertial element must have inertia element"); + return false; + } + if (!(inertia_xml->Attribute("ixx") && inertia_xml->Attribute("ixy") && inertia_xml->Attribute("ixz") && + inertia_xml->Attribute("iyy") && inertia_xml->Attribute("iyz") && + inertia_xml->Attribute("izz"))) + { + ROS_ERROR("Inertial: inertia element must have ixx,ixy,ixz,iyy,iyz,izz attributes"); + return false; + } + ixx = atof(inertia_xml->Attribute("ixx")); + ixy = atof(inertia_xml->Attribute("ixy")); + ixz = atof(inertia_xml->Attribute("ixz")); + iyy = atof(inertia_xml->Attribute("iyy")); + iyz = atof(inertia_xml->Attribute("iyz")); + izz = atof(inertia_xml->Attribute("izz")); + + return true; +} + +bool Visual::initXml(TiXmlElement *config) +{ + this->clear(); + + // Origin + TiXmlElement *o = config->FirstChildElement("origin"); + if (!o) + { + ROS_DEBUG("Origin tag not present for visual element, using default (Identity)"); + this->origin.clear(); + } + else if (!this->origin.initXml(o)) + { + ROS_ERROR("Visual has a malformed origin tag"); + this->origin.clear(); + return false; + } + + // Geometry + TiXmlElement *geom = config->FirstChildElement("geometry"); + geometry = parseGeometry(geom); + if (!geometry) + { + ROS_ERROR("Malformed geometry for Visual element"); + return false; + } + + // Material + TiXmlElement *mat = config->FirstChildElement("material"); + if (!mat) + { + ROS_DEBUG("visual element has no material tag."); + } + else + { + // get material name + if (!mat->Attribute("name")) + { + ROS_ERROR("Visual material must contain a name attribute"); + return false; + } + this->material_name = mat->Attribute("name"); + + // try to parse material element in place + this->material.reset(new Material); + if (!this->material->initXml(mat)) + { + ROS_DEBUG("Could not parse material element in Visual block, maybe defined outside."); + this->material.reset(); + } + else + { + ROS_DEBUG("Parsed material element in Visual block."); + } + } + + return true; +} + +bool Collision::initXml(TiXmlElement* config) +{ + this->clear(); + + // Origin + TiXmlElement *o = config->FirstChildElement("origin"); + if (!o) + { + ROS_INFO("Origin tag not present for collision element, using default (Identity)"); + this->origin.clear(); + } + else if (!this->origin.initXml(o)) + { + ROS_ERROR("Collision has a malformed origin tag"); + this->origin.clear(); + return false; + } + + // Geometry + TiXmlElement *geom = config->FirstChildElement("geometry"); + geometry = parseGeometry(geom); + if (!geometry) + { + ROS_ERROR("Malformed geometry for Collision element"); + return false; + } + + return true; +} + +bool Sphere::initXml(TiXmlElement *c) +{ + this->clear(); + + this->type = SPHERE; + if (!c->Attribute("radius")) + { + ROS_ERROR("Sphere shape must have a radius attribute"); + return false; + } + + radius = atof(c->Attribute("radius")); + return false; +} + +bool Box::initXml(TiXmlElement *c) +{ + this->clear(); + + this->type = BOX; + if (!c->Attribute("size")) + { + ROS_ERROR("Box shape has no size attribute"); + return false; + } + if (!dim.init(c->Attribute("size"))) + { + ROS_ERROR("Box shape has malformed size attribute"); + dim.clear(); + return false; + } + return true; +} + +bool Cylinder::initXml(TiXmlElement *c) +{ + this->clear(); + + this->type = CYLINDER; + if (!c->Attribute("length") || + !c->Attribute("radius")) + { + ROS_ERROR("Cylinder shape must have both length and radius attributes"); + return false; + } + + length = atof(c->Attribute("length")); + radius = atof(c->Attribute("radius")); + return true; +} + +bool Mesh::initXml(TiXmlElement *c) +{ + this->clear(); + + this->type = MESH; + if (!c->Attribute("filename")) + { + ROS_ERROR("Mesh must contain a filename attribute"); + return false; + } + + filename = c->Attribute("filename"); + + if (c->Attribute("scale")) + { + if (!this->scale.init(c->Attribute("scale"))) + { + ROS_ERROR("Mesh scale was specified, but could not be parsed"); + this->scale.clear(); + return false; + } + } + else + ROS_DEBUG("Mesh scale was not specified, default to (1,1,1)"); + + return true; +} + + +bool Link::initXml(TiXmlElement* config) +{ + this->clear(); + + const char *name_char = config->Attribute("name"); + if (!name_char) + { + ROS_ERROR("No name given for the link."); + return false; + } + name = std::string(name_char); + + // Inertial + TiXmlElement *i = config->FirstChildElement("inertial"); + if (i) + { + inertial.reset(new Inertial); + if (!inertial->initXml(i)) + { + ROS_ERROR("Could not parse inertial element for Link '%s'", this->name.c_str()); + inertial.reset(); + } + } + + // Visual + TiXmlElement *v = config->FirstChildElement("visual"); + if (v) + { + visual.reset(new Visual); + if (!visual->initXml(v)) + { + ROS_ERROR("Could not parse visual element for Link '%s'", this->name.c_str()); + visual.reset(); + } + } + + // Collision + TiXmlElement *col = config->FirstChildElement("collision"); + if (col) + { + collision.reset(new Collision); + if (!collision->initXml(col)) + { + ROS_ERROR("Could not parse collision element for Link '%s'", this->name.c_str()); + collision.reset(); + } + } + + return true; +} + +void Link::setParent(boost::shared_ptr parent) +{ + this->parent_link = parent; + ROS_DEBUG("set parent Link '%s' for Link '%s'", parent->name.c_str(), this->name.c_str()); +} + +void Link::setParentJoint(boost::shared_ptr parent) +{ + this->parent_joint = parent; + ROS_DEBUG("set parent joint '%s' to Link '%s'", parent->name.c_str(), this->name.c_str()); +} + +void Link::addChild(boost::shared_ptr child) +{ + this->child_links.push_back(child); + ROS_DEBUG("added child Link '%s' to Link '%s'", child->name.c_str(), this->name.c_str()); +} + +void Link::addChildJoint(boost::shared_ptr child) +{ + this->child_joints.push_back(child); + ROS_DEBUG("added child Joint '%s' to Link '%s'", child->name.c_str(), this->name.c_str()); +} + + + +} + diff --git a/urdf/src/model.cpp b/urdf/src/model.cpp new file mode 100644 index 0000000..106e3d5 --- /dev/null +++ b/urdf/src/model.cpp @@ -0,0 +1,409 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#include +#include +#include +#include "urdf/model.h" + +namespace urdf{ + + +Model::Model() +{ + this->clear(); +} + +void Model::clear() +{ + name_.clear(); + this->links_.clear(); + this->joints_.clear(); + this->materials_.clear(); + this->root_link_.reset(); +} + + +bool Model::initFile(const std::string& filename) +{ + TiXmlDocument xml_doc; + xml_doc.LoadFile(filename); + + return initXml(&xml_doc); +} + + +bool Model::initString(const std::string& xml_string) +{ + TiXmlDocument xml_doc; + xml_doc.Parse(xml_string.c_str()); + + return initXml(&xml_doc); +} + + +bool Model::initXml(TiXmlDocument *xml_doc) +{ + if (!xml_doc) + { + ROS_ERROR("Could not parse the xml"); + return false; + } + + TiXmlElement *robot_xml = xml_doc->FirstChildElement("robot"); + if (!robot_xml) + { + ROS_ERROR("Could not find the 'robot' element in the xml file"); + return false; + } + return initXml(robot_xml); +} + +bool Model::initXml(TiXmlElement *robot_xml) +{ + this->clear(); + + ROS_DEBUG("Parsing robot xml"); + if (!robot_xml) return false; + + // Get robot name + const char *name = robot_xml->Attribute("name"); + if (!name) + { + ROS_ERROR("No name given for the robot."); + return false; + } + this->name_ = std::string(name); + + // Get all Material elements + for (TiXmlElement* material_xml = robot_xml->FirstChildElement("material"); material_xml; material_xml = material_xml->NextSiblingElement("material")) + { + boost::shared_ptr material; + material.reset(new Material); + + if (material->initXml(material_xml)) + { + if (this->getMaterial(material->name)) + { + ROS_ERROR("material '%s' is not unique.", material->name.c_str()); + material.reset(); + return false; + } + else + { + this->materials_.insert(make_pair(material->name,material)); + ROS_DEBUG("successfully added a new material '%s'", material->name.c_str()); + } + } + else + { + ROS_ERROR("material xml is not initialized correctly"); + material.reset(); + } + } + + // Get all Link elements + for (TiXmlElement* link_xml = robot_xml->FirstChildElement("link"); link_xml; link_xml = link_xml->NextSiblingElement("link")) + { + boost::shared_ptr link; + link.reset(new Link); + + if (link->initXml(link_xml)) + { + if (this->getLink(link->name)) + { + ROS_ERROR("link '%s' is not unique.", link->name.c_str()); + link.reset(); + return false; + } + else + { + // set link visual material + ROS_DEBUG("setting link '%s' material", link->name.c_str()); + if (link->visual) + { + if (!link->visual->material_name.empty()) + { + if (this->getMaterial(link->visual->material_name)) + { + ROS_DEBUG("setting link '%s' material to '%s'", link->name.c_str(),link->visual->material_name.c_str()); + link->visual->material = this->getMaterial( link->visual->material_name.c_str() ); + } + else + { + if (link->visual->material) + { + ROS_DEBUG("link '%s' material '%s' defined in Visual.", link->name.c_str(),link->visual->material_name.c_str()); + this->materials_.insert(make_pair(link->visual->material->name,link->visual->material)); + } + else + { + ROS_ERROR("link '%s' material '%s' undefined.", link->name.c_str(),link->visual->material_name.c_str()); + link.reset(); + return false; + } + } + } + } + + this->links_.insert(make_pair(link->name,link)); + ROS_DEBUG("successfully added a new link '%s'", link->name.c_str()); + } + } + else + { + ROS_ERROR("link xml is not initialized correctly"); + link.reset(); + } + } + // Get all Joint elements + for (TiXmlElement* joint_xml = robot_xml->FirstChildElement("joint"); joint_xml; joint_xml = joint_xml->NextSiblingElement("joint")) + { + boost::shared_ptr joint; + joint.reset(new Joint); + + if (joint->initXml(joint_xml)) + { + if (this->getJoint(joint->name)) + { + ROS_ERROR("joint '%s' is not unique.", joint->name.c_str()); + joint.reset(); + return false; + } + else + { + this->joints_.insert(make_pair(joint->name,joint)); + ROS_DEBUG("successfully added a new joint '%s'", joint->name.c_str()); + } + } + else + { + ROS_ERROR("joint xml is not initialized correctly"); + joint.reset(); + } + } + + + // every link has children links and joints, but no parents, so we create a + // local convenience data structure for keeping child->parent relations + std::map parent_link_tree; + parent_link_tree.clear(); + + // building tree: name mapping + if (!this->initTree(parent_link_tree)) + { + ROS_ERROR("failed to build tree"); + return false; + } + + // find the root link + if (!this->initRoot(parent_link_tree)) + { + ROS_ERROR("failed to find root link"); + return false; + } + + return true; +} + +bool Model::initTree(std::map &parent_link_tree) +{ + // loop through all joints, for every link, assign children links and children joints + for (std::map >::iterator joint = this->joints_.begin();joint != this->joints_.end(); joint++) + { + std::string parent_link_name = joint->second->parent_link_name; + std::string child_link_name = joint->second->child_link_name; + + ROS_DEBUG("build tree: joint: '%s' has parent link '%s' and child link '%s'", joint->first.c_str(), parent_link_name.c_str(),child_link_name.c_str()); + + /// add an empty "world" link + if (parent_link_name == "world") + { + if (this->getLink(parent_link_name)) + { + ROS_DEBUG(" parent link '%s' already exists.", parent_link_name.c_str()); + } + else + { + ROS_DEBUG(" parent link '%s' is a special case, adding fake link.", parent_link_name.c_str()); + boost::shared_ptr link; + link.reset(new Link); + link->name = "world"; + this->links_.insert(make_pair(link->name,link)); + ROS_DEBUG(" successfully added new link '%s'", link->name.c_str()); + } + } + + if (parent_link_name.empty()) + { + ROS_DEBUG(" Joint %s: does not have parent link name specified. Joint is an abstract joint.",(joint->second)->name.c_str()); + } + else if (child_link_name.empty()) + { + ROS_DEBUG(" Joint %s: does not have child link name specified. Joint is an abstract joint.",(joint->second)->name.c_str()); + } + else + { + // find parent link + boost::shared_ptr parent_link; + this->getLink(parent_link_name, parent_link); + + if (!parent_link) + { + ROS_ERROR(" parent link '%s' is not found", parent_link_name.c_str()); + return false; + } + else + { + // find child link + boost::shared_ptr child_link; + this->getLink(child_link_name, child_link); + + if (!child_link) + { + ROS_ERROR(" for joint: %s child link '%s' is not found",joint->first.c_str(),child_link_name.c_str()); + return false; + } + else + { + //set parent link for child link + child_link->setParent(parent_link); + + //set parent joint for child link + child_link->setParentJoint(joint->second); + + //set child joint for parent link + parent_link->addChildJoint(joint->second); + + //set child link for parent link + parent_link->addChild(child_link); + + // fill in child/parent string map + parent_link_tree[child_link->name] = parent_link_name; + + ROS_DEBUG(" now Link '%s' has %i children ", parent_link->name.c_str(), (int)parent_link->child_links.size()); + } + } + } + } + + return true; +} + + + +bool Model::initRoot(std::map &parent_link_tree) +{ + + this->root_link_.reset(); + + for (std::map::iterator p=parent_link_tree.begin(); p!=parent_link_tree.end(); p++) + { + if (parent_link_tree.find(p->second) == parent_link_tree.end()) + { + if (this->root_link_) + { + ROS_DEBUG("child '%s', parent '%s', root '%s'", p->first.c_str(), p->second.c_str(), this->root_link_->name.c_str()); + if (this->root_link_->name != p->second) + { + ROS_ERROR("Two root links found: '%s' and '%s'", this->root_link_->name.c_str(), p->second.c_str()); + return false; + } + } + else + getLink(p->second,this->root_link_); + } + } + if (!this->root_link_) + { + ROS_ERROR("No root link found. The robot xml is empty or not a tree."); + return false; + } + ROS_DEBUG("Link '%s' is the root link", this->root_link_->name.c_str()); + + return true; +} + +boost::shared_ptr Model::getMaterial(const std::string& name) const +{ + boost::shared_ptr ptr; + if (this->materials_.find(name) == this->materials_.end()) + ptr.reset(); + else + ptr = this->materials_.find(name)->second; + return ptr; +} + +boost::shared_ptr Model::getLink(const std::string& name) const +{ + boost::shared_ptr ptr; + if (this->links_.find(name) == this->links_.end()) + ptr.reset(); + else + ptr = this->links_.find(name)->second; + return ptr; +} + +void Model::getLinks(std::vector >& links) const +{ + for (std::map >::const_iterator link = this->links_.begin();link != this->links_.end(); link++) + { + links.push_back(link->second); + } +} + +void Model::getLink(const std::string& name,boost::shared_ptr &link) const +{ + boost::shared_ptr ptr; + if (this->links_.find(name) == this->links_.end()) + ptr.reset(); + else + ptr = this->links_.find(name)->second; + link = ptr; +} + +boost::shared_ptr Model::getJoint(const std::string& name) const +{ + boost::shared_ptr ptr; + if (this->joints_.find(name) == this->joints_.end()) + ptr.reset(); + else + ptr = this->joints_.find(name)->second; + return ptr; +} + +} + diff --git a/urdf/test/parse_test.cpp b/urdf/test/parse_test.cpp new file mode 100644 index 0000000..93f6b6f --- /dev/null +++ b/urdf/test/parse_test.cpp @@ -0,0 +1,104 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#include "urdf/model.h" +#include + +using namespace urdf; + +void printTree(boost::shared_ptr link,int level = 0) +{ + level+=2; + int count = 0; + for (std::vector >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) + { + if (*child) + { + for(int j=0;jname + << " with mass: " << (*child)->inertial->mass + << std::endl; + // first grandchild + printTree(*child,level); + } + else + { + for(int j=0;jname << " has a null child!" << *child << std::endl; + } + } + +} + + +int main(int argc, char** argv) +{ + if (argc < 2){ + std::cerr << "Expect xml file to parse" << std::endl; + return -1; + } + TiXmlDocument robot_model_xml; + robot_model_xml.LoadFile(argv[1]); + TiXmlElement *robot_xml = robot_model_xml.FirstChildElement("robot"); + if (!robot_xml){ + std::cerr << "ERROR: Could not load the xml into TiXmlElement" << std::endl; + return -1; + } + + Model robot; + if (!robot.initXml(robot_xml)){ + std::cerr << "ERROR: Model Parsing the xml failed" << std::endl; + return -1; + } + + std::cout << "robot name is: " << robot.getName() << std::endl; + + // get info from parser + std::cout << "---------- Finished Loading from Model XML, Now Checking Model structure ------------" << std::endl; + // get root link + boost::shared_ptr root_link=robot.getRoot(); + if (!root_link) return -1; + + std::cout << "root Link: " << root_link->name << std::endl; + if (!root_link->child_links.empty()) + std::cout << "root Link: " << root_link->name << " has " << root_link->child_links.size() << " children" << std::endl; + + + // print entire tree + printTree(root_link); + return 0; +} + diff --git a/urdf/test/pr2_desc.xml b/urdf/test/pr2_desc.xml new file mode 100644 index 0000000..46efbc9 --- /dev/null +++ b/urdf/test/pr2_desc.xml @@ -0,0 +1,2542 @@ + + + + + + + + + + + + + + + + + + + true + 1000.0 + + + + + + true + 1.0 + 5 + -10.0 + 1.0 + 10.0 + 1200000.0 + diagnostic + battery_state + self_test + + + + + true + 1000.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + fl_caster_l_wheel_collision + 100.0 + + true + 100.0 + fl_caster_l_wheel_bumper + + + + + + + + + + + + + + 75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + fl_caster_r_wheel_collision + 100.0 + + true + 100.0 + fl_caster_r_wheel_bumper + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + fr_caster_l_wheel_collision + 100.0 + + true + 100.0 + fr_caster_l_wheel_bumper + + + + + + + + + + + + + + 75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + fr_caster_r_wheel_collision + 100.0 + + true + 100.0 + fr_caster_r_wheel_bumper + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + bl_caster_l_wheel_collision + 100.0 + + true + 100.0 + bl_caster_l_wheel_bumper + + + + + + + + + + + + + + 75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + bl_caster_r_wheel_collision + 100.0 + + true + 100.0 + bl_caster_r_wheel_bumper + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + br_caster_l_wheel_collision + 100.0 + + true + 100.0 + br_caster_l_wheel_bumper + + + + + + + + + + + + + + 75.05 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + br_caster_r_wheel_collision + 100.0 + + true + 100.0 + br_caster_r_wheel_bumper + + + + + + + + + + + + + + -75.05 + + + base_collision + 100.0 + + true + 100.0 + base_bumper + + + + + + + + + + true + 100.0 + base_link + base_pose_ground_truth + 0.01 + map + 25.7 25.7 0 + 0 0 0 + + + + + 640 + 640 + 1 + 0.0 0.0 0.0 + false + + -100 + 100 + + 0.05 + 10.0 + 0.01 + 20.0 + + 0.005 + true + 20.0 + base_scan + base_laser + + + + + + + + true + 100.0 + plug_magnet + plug_magnet_pose_ground_truth + 0.01 + map + 0 0 0 + 0 0 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -52143.33 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 6.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 6.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + r_shoulder_pan_collision + 100.0 + + true + 100.0 + r_shoulder_pan_bumper + + + + + true + + + + + r_shoulder_lift_collision_geom + 100.0 + + true + 100.0 + r_r_shoulder_lift_bumper + + + + true + + + + + + true + + + + + + r_upper_arm_collision_geom + 100.0 + + true + 100.0 + r_upper_arm_bumper + + + + true + + + + r_elbow_flex_collision_geom + 100.0 + + true + 100.0 + r_elbow_flex_bumper + + + + + + + true + + + + true + + true + + r_forearm_collision + 100.0 + + true + 100.0 + r_forearm_bumper + + + + + + true + + r_wrist_flex_collision + 100.0 + + true + 100.0 + r_wrist_flex_bumper + + + + + + + + true + + r_wrist_roll_collision + 100.0 + + true + 100.0 + r_wrist_roll_bumper + + + + + + + + + 63.16 + + + + 61.89 + + + + 32.65 + + + + -36.17 + + + + 90.5142857143 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + + r_gripper_l_finger_collision + 100.0 + + true + 100.0 + r_gripper_l_finger_bumper + + + + + + + + + + + + + + + true + + r_gripper_r_finger_collision + 100.0 + + true + 100.0 + r_gripper_r_finger_bumper + + + + + + + + + + + + + + + + + + true + + + r_gripper_l_finger_tip_collision + 100.0 + + true + 100.0 + r_gripper_l_finger_tip_bumper + + + + + + + + + + + + + + + + + true + + + r_gripper_r_finger_tip_collision + 100.0 + + true + 100.0 + r_gripper_r_finger_tip_bumper + + + + + + + + + + + + + + + + + true + 100.0 + r_gripper_l_finger_link + r_gripper_l_finger_pose_ground_truth + 0.0 + map + + + + true + 100.0 + r_gripper_l_finger_link + r_gripper_l_finger_force_ground_truth + r_gripper_l_finger_link + + + + + + + + + + + + + + + + true + + r_gripper_palm_collision + 100.0 + + true + 100.0 + r_gripper_palm_bumper + + + + + + true + + + r_gripper_l_finger_tip_link + r_gripper_float_link + r_gripper_l_finger_tip_link + 0 1 0 + 0 0 0 + + + r_gripper_r_finger_tip_link + r_gripper_float_link + r_gripper_r_finger_tip_link + 0 1 0 + 0 0 0 + + + + + true + 100.0 + r_gripper_palm_link + r_gripper_palm_pose_ground_truth + 0 0 0 + 0 0 0 + 0.0 + map + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + l_shoulder_pan_collision + 100.0 + + true + 100.0 + l_shoulder_pan_bumper + + + + + true + + + + + l_shoulder_lift_collision_geom + 100.0 + + true + 100.0 + l_r_shoulder_lift_bumper + + + + true + + + + + + true + + + + + + l_upper_arm_collision_geom + 100.0 + + true + 100.0 + l_upper_arm_bumper + + + + true + + + + l_elbow_flex_collision_geom + 100.0 + + true + 100.0 + l_elbow_flex_bumper + + + + + + + true + + + + true + + true + + l_forearm_collision + 100.0 + + true + 100.0 + l_forearm_bumper + + + + + + true + + l_wrist_flex_collision + 100.0 + + true + 100.0 + l_wrist_flex_bumper + + + + + + + + true + + l_wrist_roll_collision + 100.0 + + true + 100.0 + l_wrist_roll_bumper + + + + + + + + + 63.16 + + + + 61.89 + + + + 32.65 + + + + -36.17 + + + + 90.5142857143 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + + l_gripper_l_finger_collision + 100.0 + + true + 100.0 + l_gripper_l_finger_bumper + + + + + + + + + + + + + + + true + + l_gripper_r_finger_collision + 100.0 + + true + 100.0 + l_gripper_r_finger_bumper + + + + + + + + + + + + + + + + + + true + + + l_gripper_l_finger_tip_collision + 100.0 + + true + 100.0 + l_gripper_l_finger_tip_bumper + + + + + + + + + + + + + + + + + true + + + l_gripper_r_finger_tip_collision + 100.0 + + true + 100.0 + l_gripper_r_finger_tip_bumper + + + + + + + + + + + + + + + + + true + 100.0 + l_gripper_l_finger_link + l_gripper_l_finger_pose_ground_truth + 0.0 + map + + + + true + 100.0 + l_gripper_l_finger_link + l_gripper_l_finger_force_ground_truth + l_gripper_l_finger_link + + + + + + + + + + + + + + + + true + + l_gripper_palm_collision + 100.0 + + true + 100.0 + l_gripper_palm_bumper + + + + + + true + + + l_gripper_l_finger_tip_link + l_gripper_float_link + l_gripper_l_finger_tip_link + 0 1 0 + 0 0 0 + + + l_gripper_r_finger_tip_link + l_gripper_float_link + l_gripper_r_finger_tip_link + 0 1 0 + 0 0 0 + + + + + true + 100.0 + l_gripper_palm_link + l_gripper_palm_pose_ground_truth + 0 0 0 + 0 0 0 + 0.0 + map + + + + true + + + + + + + + + + + + + + + + + + + + + diff --git a/urdf/test/pr2_desc_bracket.xml b/urdf/test/pr2_desc_bracket.xml new file mode 100644 index 0000000..d0caaa8 --- /dev/null +++ b/urdf/test/pr2_desc_bracket.xml @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/urdf/test/pr2_desc_double.xml b/urdf/test/pr2_desc_double.xml new file mode 100644 index 0000000..10bbd4c --- /dev/null +++ b/urdf/test/pr2_desc_double.xml @@ -0,0 +1,39 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/urdf/test/pr2_desc_double_joint.xml b/urdf/test/pr2_desc_double_joint.xml new file mode 100644 index 0000000..2974a7a --- /dev/null +++ b/urdf/test/pr2_desc_double_joint.xml @@ -0,0 +1,38 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/urdf/test/pr2_desc_loop.xml b/urdf/test/pr2_desc_loop.xml new file mode 100644 index 0000000..ab21024 --- /dev/null +++ b/urdf/test/pr2_desc_loop.xml @@ -0,0 +1,39 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/urdf/test/pr2_desc_no_joint.xml b/urdf/test/pr2_desc_no_joint.xml new file mode 100644 index 0000000..0f17fe0 --- /dev/null +++ b/urdf/test/pr2_desc_no_joint.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/urdf/test/pr2_desc_no_joint2.xml b/urdf/test/pr2_desc_no_joint2.xml new file mode 100644 index 0000000..7b37fbe --- /dev/null +++ b/urdf/test/pr2_desc_no_joint2.xml @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/urdf/test/pr2_desc_parent_itself.xml b/urdf/test/pr2_desc_parent_itself.xml new file mode 100644 index 0000000..5eda24d --- /dev/null +++ b/urdf/test/pr2_desc_parent_itself.xml @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/urdf/test/pr2_desc_two_trees.xml b/urdf/test/pr2_desc_two_trees.xml new file mode 100644 index 0000000..415e74c --- /dev/null +++ b/urdf/test/pr2_desc_two_trees.xml @@ -0,0 +1,39 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/urdf/test/test_robot_model_parser.cpp b/urdf/test/test_robot_model_parser.cpp new file mode 100644 index 0000000..efef0fb --- /dev/null +++ b/urdf/test/test_robot_model_parser.cpp @@ -0,0 +1,98 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen */ + +#include +#include +#include "urdf/model.h" + +// Including ros, just to be able to call ros::init(), to remove unwanted +// args from command-line. +#include + +using namespace urdf; + +int g_argc; +char** g_argv; + +class TestParser : public testing::Test +{ +public: + Model robot; + +protected: + /// constructor + TestParser() + { + } + + + /// Destructor + ~TestParser() + { + } +}; + + + + +TEST_F(TestParser, test) +{ + for (int i=1; i + +