Alec Jacobson 5 years ago
parent
commit
c608c60a6d

+ 3 - 0
.github/workflows/continuous.yml

@@ -141,6 +141,9 @@ jobs:
             -DLIBIGL_USE_STATIC_LIBRARY=${{ matrix.static }} ^
             -DLIBIGL_WITH_CGAL=ON ^
             -DLIBIGL_WITH_COMISO=OFF ^
+            -DCMAKE_JOB_POOLS=pool-linking=1;pool-compilation=2 ^
+            -DCMAKE_JOB_POOL_COMPILE:STRING=pool-compilation ^
+            -DCMAKE_JOB_POOL_LINK:STRING=pool-linking ^
             -B build ^
             -S .
           cmake --build build

+ 3 - 0
.github/workflows/nightly.yml

@@ -178,6 +178,9 @@ jobs:
             -DLIBIGL_BUILD_TUTORIALS=${{ matrix.tutorials }} ^
             -DLIBIGL_WITH_CGAL=ON ^
             -DLIBIGL_WITH_COMISO=OFF ^
+            -DCMAKE_JOB_POOLS=pool-linking=1;pool-compilation=2 ^
+            -DCMAKE_JOB_POOL_COMPILE:STRING=pool-compilation ^
+            -DCMAKE_JOB_POOL_LINK:STRING=pool-linking ^
             -B build ^
             -S .
           cmake --build build -j 1

+ 1 - 1
cmake/DownloadProject.CMakeLists.cmake.in

@@ -1,7 +1,7 @@
 # Distributed under the OSI-approved MIT License.  See accompanying
 # file LICENSE or https://github.com/Crascit/DownloadProject for details.
 
-cmake_minimum_required(VERSION 2.8.2)
+cmake_minimum_required(VERSION 3.1)
 
 project(${DL_ARGS_PROJ}-download NONE)
 

+ 1 - 0
include/igl/copyleft/marching_cubes.h

@@ -39,6 +39,7 @@ namespace igl
     //   vertices  #V by 3 list of mesh vertex positions
     //   faces  #F by 3 list of mesh triangle indices
     //
+    // See also: igl::marching_cubes
     template <typename DerivedValues, typename DerivedPoints, typename DerivedVertices, typename DerivedFaces>
     IGL_INLINE void marching_cubes(
         const Eigen::MatrixBase<DerivedValues> &values,

+ 0 - 64
include/igl/copyleft/offset_surface.cpp

@@ -1,64 +0,0 @@
-#include "offset_surface.h"
-#include "marching_cubes.h"
-#include "../voxel_grid.h"
-#include "../signed_distance.h"
-#include "../flood_fill.h"
-#include <cassert>
-
-template <
-  typename DerivedV,
-  typename DerivedF,
-  typename isolevelType,
-  typename DerivedSV,
-  typename DerivedSF,
-  typename DerivedGV,
-  typename Derivedside,
-  typename DerivedS>
-void igl::copyleft::offset_surface(
-  const Eigen::MatrixBase<DerivedV> & V,
-  const Eigen::MatrixBase<DerivedF> & F,
-  const isolevelType isolevel,
-  const typename Derivedside::Scalar s,
-  const SignedDistanceType & signed_distance_type,
-  Eigen::PlainObjectBase<DerivedSV> & SV,
-  Eigen::PlainObjectBase<DerivedSF> & SF,
-  Eigen::PlainObjectBase<DerivedGV> &   GV,
-  Eigen::PlainObjectBase<Derivedside> & side,
-  Eigen::PlainObjectBase<DerivedS> & S)
-{
-  typedef typename DerivedV::Scalar Scalar;
-  typedef typename DerivedF::Scalar Index;
-  {
-    Eigen::AlignedBox<Scalar,3> box;
-    typedef Eigen::Matrix<Scalar,1,3> RowVector3S;
-    assert(V.cols() == 3 && "V must contain positions in 3D");
-    RowVector3S min_ext = V.colwise().minCoeff().array() - isolevel;
-    RowVector3S max_ext = V.colwise().maxCoeff().array() + isolevel;
-    box.extend(min_ext.transpose());
-    box.extend(max_ext.transpose());
-    igl::voxel_grid(box,s,1,GV,side);
-  }
-
-  const Scalar h = 
-    (GV.col(0).maxCoeff()-GV.col(0).minCoeff())/((Scalar)(side(0)-1));
-  const Scalar lower_bound = isolevel-sqrt(3.0)*h;
-  const Scalar upper_bound = isolevel+sqrt(3.0)*h;
-  {
-    Eigen::Matrix<Index,Eigen::Dynamic,1> I;
-    Eigen::Matrix<typename DerivedV::Scalar,Eigen::Dynamic,3> C,N;
-    igl::signed_distance(
-      GV,V,F,signed_distance_type,lower_bound,upper_bound,S,I,C,N);
-  }
-  igl::flood_fill(side,S);
-  
-  DerivedS SS = S.array()-isolevel;
-  igl::copyleft::marching_cubes(SS,GV,side(0),side(1),side(2),SV,SF);
-}
-
-#ifdef IGL_STATIC_LIBRARY
-// Explicit template instantiation
-// generated by autoexplicit.sh
-template void igl::copyleft::offset_surface<Eigen::Matrix<double, -1, 3, 1, -1, 3>, Eigen::Matrix<int, -1, 3, 1, -1, 3>, double, Eigen::Matrix<double, -1, 3, 1, -1, 3>, Eigen::Matrix<int, -1, 3, 1, -1, 3>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<int, 1, 3, 1, 1, 3>, Eigen::Matrix<double, -1, 1, 0, -1, 1> >(Eigen::MatrixBase<Eigen::Matrix<double, -1, 3, 1, -1, 3> > const&, Eigen::MatrixBase<Eigen::Matrix<int, -1, 3, 1, -1, 3> > const&, double, Eigen::Matrix<int, 1, 3, 1, 1, 3>::Scalar, igl::SignedDistanceType const&, Eigen::PlainObjectBase<Eigen::Matrix<double, -1, 3, 1, -1, 3> >&, Eigen::PlainObjectBase<Eigen::Matrix<int, -1, 3, 1, -1, 3> >&, Eigen::PlainObjectBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> >&, Eigen::PlainObjectBase<Eigen::Matrix<int, 1, 3, 1, 1, 3> >&, Eigen::PlainObjectBase<Eigen::Matrix<double, -1, 1, 0, -1, 1> >&);
-template void igl::copyleft::offset_surface<Eigen::Matrix<float, -1, 3, 1, -1, 3>, Eigen::Matrix<int, -1, 3, 1, -1, 3>, float, Eigen::Matrix<float, -1, 3, 1, -1, 3>, Eigen::Matrix<int, -1, 3, 1, -1, 3>, Eigen::Matrix<float, -1, -1, 0, -1, -1>, Eigen::Matrix<int, 1, 3, 1, 1, 3>, Eigen::Matrix<float, -1, 1, 0, -1, 1> >(Eigen::MatrixBase<Eigen::Matrix<float, -1, 3, 1, -1, 3> > const&, Eigen::MatrixBase<Eigen::Matrix<int, -1, 3, 1, -1, 3> > const&, float, Eigen::Matrix<int, 1, 3, 1, 1, 3>::Scalar, igl::SignedDistanceType const&, Eigen::PlainObjectBase<Eigen::Matrix<float, -1, 3, 1, -1, 3> >&, Eigen::PlainObjectBase<Eigen::Matrix<int, -1, 3, 1, -1, 3> >&, Eigen::PlainObjectBase<Eigen::Matrix<float, -1, -1, 0, -1, -1> >&, Eigen::PlainObjectBase<Eigen::Matrix<int, 1, 3, 1, 1, 3> >&, Eigen::PlainObjectBase<Eigen::Matrix<float, -1, 1, 0, -1, 1> >&);
-template void igl::copyleft::offset_surface<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<int, -1, -1, 0, -1, -1>, double, Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<int, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<int, 1, 3, 1, 1, 3>, Eigen::Matrix<double, -1, 1, 0, -1, 1> >(Eigen::MatrixBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> > const&, Eigen::MatrixBase<Eigen::Matrix<int, -1, -1, 0, -1, -1> > const&, double, Eigen::Matrix<int, 1, 3, 1, 1, 3>::Scalar, igl::SignedDistanceType const&, Eigen::PlainObjectBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> >&, Eigen::PlainObjectBase<Eigen::Matrix<int, -1, -1, 0, -1, -1> >&, Eigen::PlainObjectBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> >&, Eigen::PlainObjectBase<Eigen::Matrix<int, 1, 3, 1, 1, 3> >&, Eigen::PlainObjectBase<Eigen::Matrix<double, -1, 1, 0, -1, 1> >&);
-#endif

+ 0 - 54
include/igl/copyleft/offset_surface.h

@@ -1,54 +0,0 @@
-#ifndef IGL_COPYLEFT_OFFSET_SURFACE_H
-#define IGL_COPYLEFT_OFFSET_SURFACE_H
-#include "../igl_inline.h"
-#include "../signed_distance.h"
-#include <Eigen/Core>
-
-namespace igl
-{
-  namespace copyleft
-  {
-    // Compute a triangulated offset surface using matching cubes on a grid of
-    // signed distance values from the input triangle mesh.
-    //
-    // Inputs:
-    //   V  #V by 3 list of mesh vertex positions
-    //   F  #F by 3 list of mesh triangle indices into V
-    //   isolevel  iso level to extract (signed distance: negative inside)
-    //   s  number of grid cells along longest side (controls resolution)
-    //   signed_distance_type  type of signing to use (see
-    //     ../signed_distance.h)
-    // Outputs:
-    //   SV  #SV by 3 list of output surface mesh vertex positions
-    //   SF  #SF by 3 list of output mesh triangle indices into SV
-    //   GV  #GV=side(0)*side(1)*side(2) by 3 list of grid cell centers
-    //   side  list of number of grid cells in x, y, and z directions
-    //   S  #GV by 3 list of signed distance values _near_ `isolevel` ("far"
-    //     from `isolevel` these values are incorrect)
-    //
-    template <
-      typename DerivedV,
-      typename DerivedF,
-      typename isolevelType,
-      typename DerivedSV,
-      typename DerivedSF,
-      typename DerivedGV,
-      typename Derivedside,
-      typename DerivedS>
-    void offset_surface(
-      const Eigen::MatrixBase<DerivedV> & V,
-      const Eigen::MatrixBase<DerivedF> & F,
-      const isolevelType isolevel,
-      const typename Derivedside::Scalar s,
-      const SignedDistanceType & signed_distance_type,
-      Eigen::PlainObjectBase<DerivedSV> & SV,
-      Eigen::PlainObjectBase<DerivedSF> & SF,
-      Eigen::PlainObjectBase<DerivedGV> & GV,
-      Eigen::PlainObjectBase<Derivedside> & side,
-      Eigen::PlainObjectBase<DerivedS> & S);
-  }
-}
-#ifndef IGL_STATIC_LIBRARY
-#  include "offset_surface.cpp"
-#endif 
-#endif 

+ 0 - 41
include/igl/copyleft/swept_volume.h

@@ -1,41 +0,0 @@
-#ifndef IGL_COPYLEFT_SWEPT_VOLUME_H
-#define IGL_COPYLEFT_SWEPT_VOLUME_H
-#include "../igl_inline.h"
-#include <Eigen/Core>
-#include <Eigen/Geometry>
-namespace igl
-{
-  namespace copyleft
-  {
-    // Compute the surface of the swept volume of a solid object with surface
-    // (V,F) mesh under going rigid motion.
-    // 
-    // Inputs:
-    //   V  #V by 3 list of mesh positions in reference pose
-    //   F  #F by 3 list of mesh indices into V
-    //   transform  function handle so that transform(t) returns the rigid
-    //     transformation at time t∈[0,1]
-    //   steps  number of time steps: steps=3 --> t∈{0,0.5,1}
-    //   grid_res  number of grid cells on the longest side containing the
-    //     motion (isolevel+1 cells will also be added on each side as padding)
-    //   isolevel  distance level to be contoured as swept volume
-    // Outputs:
-    //   SV  #SV by 3 list of mesh positions of the swept surface
-    //   SF  #SF by 3 list of mesh faces into SV
-    IGL_INLINE void swept_volume(
-      const Eigen::MatrixXd & V,
-      const Eigen::MatrixXi & F,
-      const std::function<Eigen::Affine3d(const double t)> & transform,
-      const size_t steps,
-      const size_t grid_res,
-      const size_t isolevel,
-      Eigen::MatrixXd & SV,
-      Eigen::MatrixXi & SF);
-  }
-}
-
-#ifndef IGL_STATIC_LIBRARY
-#  include "swept_volume.cpp"
-#endif
-
-#endif

+ 86 - 0
include/igl/embree/EmbreeDevice.h

@@ -0,0 +1,86 @@
+// This file is part of libigl, a simple c++ geometry processing library.
+//
+// Copyright (C) 2020 Vladimir Fonov <[email protected]>
+//               2013 Alec Jacobson <[email protected]>
+//               2014 Christian Schüller <[email protected]>
+//
+// This Source Code Form is subject to the terms of the Mozilla Public License
+// v. 2.0. If a copy of the MPL was not distributed with this file, You can
+// obtain one at http://mozilla.org/MPL/2.0/.
+//
+
+#ifndef IGL_EMBREE_EMBREE_DEVICE_H
+#define IGL_EMBREE_EMBREE_DEVICE_H
+#include <embree3/rtcore.h>
+#include <iostream>
+
+namespace igl
+{
+  namespace embree
+  {
+     // keep track of embree device
+     struct EmbreeDevice
+     {
+        RTCDevice embree_device;
+        int       embree_device_cntr;
+
+        static EmbreeDevice & instance()
+        {
+            static EmbreeDevice s;
+            return s;
+        } // instance
+
+        EmbreeDevice(const EmbreeDevice &) = delete;
+        EmbreeDevice & operator = (const EmbreeDevice &) = delete;
+
+        static RTCDevice get_device(const char *config=nullptr)
+        {
+            return instance().get(config);
+        }
+
+        static void release_device(void)
+        {
+            instance().release();
+        }
+
+    private:
+
+        EmbreeDevice():embree_device(nullptr),embree_device_cntr(0) {}
+
+        ~EmbreeDevice() 
+        { 
+            if(embree_device)
+                rtcReleaseDevice(embree_device);
+        }
+
+        RTCDevice get(const char *config=nullptr) 
+        {
+            if(!embree_device) 
+            {
+                embree_device = rtcNewDevice (config);
+                if(rtcGetDeviceError (embree_device) != RTC_ERROR_NONE)
+                    std::cerr << "Embree: An error occurred while initializing embree core!" << std::endl;
+            #ifdef IGL_VERBOSE
+                else
+                    std::cerr << "Embree: core initialized." << std::endl;
+            #endif
+            }
+            ++embree_device_cntr;
+            return embree_device;
+        }
+
+        void release()
+        {
+            if(!--embree_device_cntr) {
+                rtcReleaseDevice (embree_device);
+                embree_device = nullptr;                
+            #ifdef IGL_VERBOSE
+                    std::cerr << "Embree: core released." << std::endl;
+            #endif
+            }
+        }
+     };
+  }
+}
+
+#endif // IGL_EMBREE_EMBREE_DEVICE_H

+ 14 - 50
include/igl/embree/EmbreeIntersector.h

@@ -19,27 +19,20 @@
 #include "../Hit.h"
 #include <Eigen/Geometry>
 #include <Eigen/Core>
-#include <Eigen/Geometry>
 
 #include <embree3/rtcore.h>
 #include <embree3/rtcore_ray.h>
 #include <iostream>
 #include <vector>
 
+#include "EmbreeDevice.h"
+
 namespace igl
 {
   namespace embree
   {
     class EmbreeIntersector
     {
-    public:
-      // Initialize embree engine. This will be called on instance `init()`
-      // calls. If already inited then this function does nothing: it is harmless
-      // to call more than once.
-      static inline void global_init();
-    private:
-      // Deinitialize the embree engine.
-      static inline void global_deinit();
     public:
       typedef Eigen::Matrix<float,Eigen::Dynamic,3> PointMatrixType;
       typedef Eigen::Matrix<int,Eigen::Dynamic,3> FaceMatrixType;
@@ -176,6 +169,8 @@ namespace igl
       Triangle* triangles;
       bool initialized;
 
+      RTCDevice device;
+
       inline void createRay(
         RTCRayHit& ray,
         const Eigen::RowVector3f& origin,
@@ -189,39 +184,7 @@ namespace igl
 
 // Implementation
 #include <igl/EPS.h>
-// This unfortunately cannot be a static field of EmbreeIntersector because it
-// would depend on the template and then we might end up with initializing
-// embree twice. If only there was a way to ask embree if it's already
-// initialized...
-namespace igl
-{
-  namespace embree
-  {
-    // Keeps track of whether the **Global** Embree intersector has been
-    // initialized. This should never been done at the global scope.
-    static RTCDevice g_device = nullptr;
-  }
-}
 
-inline void igl::embree::EmbreeIntersector::global_init()
-{
-  if(!g_device)
-  {
-    g_device = rtcNewDevice (NULL);
-    if(rtcGetDeviceError (g_device) != RTC_ERROR_NONE)
-      std::cerr << "Embree: An error occurred while initializing embree core!" << std::endl;
-#ifdef IGL_VERBOSE
-    else
-      std::cerr << "Embree: core initialized." << std::endl;
-#endif
-  }
-}
-
-inline void igl::embree::EmbreeIntersector::global_deinit()
-{
-  rtcReleaseDevice (g_device);
-  g_device = nullptr;
-}
 
 inline igl::embree::EmbreeIntersector::EmbreeIntersector()
   :
@@ -229,7 +192,8 @@ inline igl::embree::EmbreeIntersector::EmbreeIntersector()
   geomID(0),
   vertices(NULL),
   triangles(NULL),
-  initialized(false)
+  initialized(false),
+  device(igl::embree::EmbreeDevice::get_device())
 {
 }
 
@@ -278,8 +242,7 @@ inline void igl::embree::EmbreeIntersector::init(
     deinit();
 
   using namespace std;
-  global_init();
-
+  
   if(V.size() == 0 || F.size() == 0)
   {
     std::cerr << "Embree: No geometry specified!";
@@ -289,14 +252,14 @@ inline void igl::embree::EmbreeIntersector::init(
   RTCBuildQuality buildQuality = isStatic ? RTC_BUILD_QUALITY_HIGH : RTC_BUILD_QUALITY_MEDIUM;
 
   // create a scene
-  scene = rtcNewScene(g_device);
+  scene = rtcNewScene(device);
   rtcSetSceneFlags(scene, RTC_SCENE_FLAG_ROBUST);
   rtcSetSceneBuildQuality(scene, buildQuality);
 
   for(int g=0;g<(int)V.size();g++)
   {
     // create triangle mesh geometry in that scene
-    RTCGeometry geom_0 = rtcNewGeometry (g_device, RTC_GEOMETRY_TYPE_TRIANGLE);
+    RTCGeometry geom_0 = rtcNewGeometry (device, RTC_GEOMETRY_TYPE_TRIANGLE);
     rtcSetGeometryBuildQuality(geom_0,buildQuality);
     rtcSetGeometryTimeStepCount(geom_0,1);
     geomID = rtcAttachGeometry(scene,geom_0);
@@ -328,7 +291,7 @@ inline void igl::embree::EmbreeIntersector::init(
 
   rtcCommitScene(scene);
 
-  if(rtcGetDeviceError (g_device) != RTC_ERROR_NONE)
+  if(rtcGetDeviceError (device) != RTC_ERROR_NONE)
       std::cerr << "Embree: An error occurred while initializing the provided geometry!" << endl;
 #ifdef IGL_VERBOSE
   else
@@ -343,15 +306,16 @@ igl::embree::EmbreeIntersector
 {
   if(initialized)
     deinit();
+  igl::embree::EmbreeDevice::release_device();
 }
 
 void igl::embree::EmbreeIntersector::deinit()
 {
-  if(g_device && scene)
+  if(device && scene)
   {
     rtcReleaseScene(scene);
 
-    if(rtcGetDeviceError (g_device) != RTC_ERROR_NONE)
+    if(rtcGetDeviceError (device) != RTC_ERROR_NONE)
     {
         std::cerr << "Embree: An error occurred while resetting!" << std::endl;
     }
@@ -386,7 +350,7 @@ inline bool igl::embree::EmbreeIntersector::intersectRay(
     ray.hit.Ng_z = -ray.hit.Ng_z;
   }
 #ifdef IGL_VERBOSE
-  if(rtcGetDeviceError (g_device) != RTC_ERROR_NONE)
+  if(rtcGetDeviceError (device) != RTC_ERROR_NONE)
       std::cerr << "Embree: An error occurred while resetting!" << std::endl;
 #endif
 

+ 423 - 0
include/igl/embree/EmbreeRenderer.cpp

@@ -0,0 +1,423 @@
+#include "EmbreeRenderer.h"
+// Implementation
+
+//IGL viewing parts
+#include "../unproject.h"
+#include "../look_at.h"
+#include "../frustum.h"
+#include "../ortho.h"
+
+// color map
+#include "../jet.h"
+
+#include "../PI.h"
+
+
+IGL_INLINE void igl::embree::EmbreeRenderer::init_view()
+{
+  camera_base_zoom = 1.0f;
+  camera_zoom = 1.0f;
+
+  camera_view_angle = 45.0;
+  camera_dnear = 1.0;
+  camera_dfar = 100.0;
+  camera_base_translation << 0, 0, 0;
+  camera_translation << 0, 0, 0;
+  camera_eye << 0, 0, 5;
+  camera_center << 0, 0, 0;
+  camera_up << 0, 1, 0;
+  
+  rot_matrix = Eigen::Matrix3f::Identity();
+
+  view = Eigen::Matrix4f::Identity();
+  proj = Eigen::Matrix4f::Identity();
+  norm = Eigen::Matrix4f::Identity();
+
+  orthographic = false;
+  
+
+  uC << 1,0,0;
+}
+
+IGL_INLINE igl::embree::EmbreeRenderer::EmbreeRenderer()
+  :
+  scene(NULL),
+  geomID(0),
+  initialized(false),
+  device(igl::embree::EmbreeDevice::get_device())
+{
+  init_view();
+}
+
+IGL_INLINE igl::embree::EmbreeRenderer::EmbreeRenderer(
+  const EmbreeRenderer &)
+  :// To make -Weffc++ happy
+  scene(NULL),
+  geomID(0),
+  initialized(false)
+{
+  assert(false && "Embree: Copying EmbreeRenderer is not allowed");
+}
+
+IGL_INLINE igl::embree::EmbreeRenderer & igl::embree::EmbreeRenderer::operator=(
+  const EmbreeRenderer &)
+{
+  assert(false && "Embree: Assigning an EmbreeRenderer is not allowed");
+  return *this;
+}
+
+
+IGL_INLINE void igl::embree::EmbreeRenderer::init(
+  const PointMatrixType& V,
+  const FaceMatrixType& F,
+  bool isStatic)
+{
+  std::vector<const PointMatrixType*> Vtemp;
+  std::vector<const FaceMatrixType*> Ftemp;
+  std::vector<int> masks;
+  Vtemp.push_back(&V);
+  Ftemp.push_back(&F);
+  masks.push_back(0xFFFFFFFF);
+  init(Vtemp,Ftemp,masks,isStatic);
+}
+
+IGL_INLINE void igl::embree::EmbreeRenderer::init(
+  const std::vector<const PointMatrixType*>& V,
+  const std::vector<const FaceMatrixType*>&  F,
+  const std::vector<int>& masks,
+  bool isStatic)
+{
+  if(initialized)
+    deinit();
+
+  using namespace std;
+
+  if(V.size() == 0 || F.size() == 0)
+  {
+    std::cerr << "Embree: No geometry specified!";
+    return;
+  }
+  RTCBuildQuality buildQuality = isStatic ? RTC_BUILD_QUALITY_HIGH : RTC_BUILD_QUALITY_MEDIUM;
+
+  // create a scene
+  scene = rtcNewScene(device);
+  rtcSetSceneFlags(scene, RTC_SCENE_FLAG_ROBUST);
+  rtcSetSceneBuildQuality(scene, buildQuality);
+
+  for(int g=0;g<(int)V.size();g++)
+  {
+    // create triangle mesh geometry in that scene
+    RTCGeometry geom_0 = rtcNewGeometry (device, RTC_GEOMETRY_TYPE_TRIANGLE);
+    rtcSetGeometryBuildQuality(geom_0, buildQuality);
+    rtcSetGeometryTimeStepCount(geom_0,1);
+    geomID = rtcAttachGeometry(scene,geom_0);
+    rtcReleaseGeometry(geom_0);
+
+    // fill vertex buffer, have to be 16 byte wide( sizeof(float)*4 )
+    Eigen::Map<Eigen::Matrix<float,-1,4,Eigen::RowMajor>> vertices(
+        (float*)rtcSetNewGeometryBuffer(geom_0,RTC_BUFFER_TYPE_VERTEX,0,RTC_FORMAT_FLOAT3,4*sizeof(float),V[g]->rows()),
+        V[g]->rows(),4
+    );
+    vertices.block(0,0,V[g]->rows(),3) = V[g]->cast<float>();
+
+    // fill triangle buffer
+    Eigen::Map<Eigen::Matrix<unsigned int,-1,3,Eigen::RowMajor>> triangles(
+      (unsigned int*) rtcSetNewGeometryBuffer(geom_0,RTC_BUFFER_TYPE_INDEX,0,RTC_FORMAT_UINT3,3*sizeof(unsigned int), F[g]->rows()),
+      F[g]->rows(),3
+    );
+    triangles = F[g]->cast<unsigned int>();
+    //TODO: store vertices and triangles in array for whatever reason?
+
+    rtcSetGeometryMask(geom_0, masks[g]);
+    rtcCommitGeometry(geom_0);
+  }
+
+  rtcCommitScene(scene);
+
+  if(rtcGetDeviceError (device) != RTC_ERROR_NONE)
+      std::cerr << "Embree: An error occurred while initializing the provided geometry!" << endl;
+#ifdef IGL_VERBOSE
+  else
+    std::cerr << "Embree: geometry added." << endl;
+#endif
+
+  initialized = true;
+}
+
+IGL_INLINE igl::embree::EmbreeRenderer::~EmbreeRenderer()
+{
+  if(initialized)
+    deinit();
+  
+  igl::embree::EmbreeDevice::release_device();
+}
+
+IGL_INLINE void igl::embree::EmbreeRenderer::deinit()
+{
+  if(scene)
+  {
+    rtcReleaseScene(scene);
+
+    if(rtcGetDeviceError (device) != RTC_ERROR_NONE)
+    {
+        std::cerr << "Embree: An error occurred while resetting!" << std::endl;
+    }
+#ifdef IGL_VERBOSE
+    else
+    {
+      std::cerr << "Embree: geometry removed." << std::endl;
+    }
+#endif
+  }
+}
+
+IGL_INLINE bool igl::embree::EmbreeRenderer::intersect_ray(
+  const Eigen::RowVector3f& origin,
+  const Eigen::RowVector3f& direction,
+  Hit&  hit,
+  float tnear,
+  float tfar,
+  int mask) const
+{
+  RTCRayHit ray;
+  ray.ray.flags = 0;
+  create_ray(ray, origin,direction,tnear,tfar,mask);
+
+  // shot ray
+  {
+    RTCIntersectContext context;
+    rtcInitIntersectContext(&context);
+    rtcIntersect1(scene, &context, &ray);
+    ray.hit.Ng_x = -ray.hit.Ng_x; // EMBREE_FIXME: only correct for triangles,quads, and subdivision surfaces
+    ray.hit.Ng_y = -ray.hit.Ng_y;
+    ray.hit.Ng_z = -ray.hit.Ng_z;
+  }
+#ifdef IGL_VERBOSE
+  if(rtcGetDeviceError (device) != RTC_ERROR_NONE)
+      std::cerr << "Embree: An error occurred while resetting!" << std::endl;
+#endif
+
+  if((unsigned)ray.hit.geomID != RTC_INVALID_GEOMETRY_ID)
+  {
+    hit.id = ray.hit.primID;
+    hit.gid = ray.hit.geomID;
+    hit.u = ray.hit.u;
+    hit.v = ray.hit.v;
+    hit.t = ray.ray.tfar;
+    hit.N = Vec3f(ray.hit.Ng_x, ray.hit.Ng_y, ray.hit.Ng_z);
+    return true;
+  }
+
+  return false;
+}
+
+IGL_INLINE void 
+igl::embree::EmbreeRenderer
+::create_ray(RTCRayHit& ray, const Eigen::RowVector3f& origin, 
+ const Eigen::RowVector3f& direction, float tnear, float tfar, int mask) const
+{
+  ray.ray.org_x = origin[0];
+  ray.ray.org_y = origin[1];
+  ray.ray.org_z = origin[2];
+  ray.ray.dir_x = direction[0];
+  ray.ray.dir_y = direction[1];
+  ray.ray.dir_z = direction[2];
+  ray.ray.tnear = tnear;
+  ray.ray.tfar = tfar;
+  ray.ray.id = RTC_INVALID_GEOMETRY_ID;
+  ray.ray.mask = mask;
+  ray.ray.time = 0.0f;
+
+  ray.hit.geomID = RTC_INVALID_GEOMETRY_ID;
+  ray.hit.instID[0] = RTC_INVALID_GEOMETRY_ID;
+  ray.hit.primID = RTC_INVALID_GEOMETRY_ID;
+}
+
+
+IGL_INLINE void
+igl::embree::EmbreeRenderer
+::set_mesh(const Eigen::Matrix<double,Eigen::Dynamic,3> & MV,
+           const Eigen::Matrix<int,  Eigen::Dynamic,3>  & MF,
+           bool is_static)
+{
+  V = MV.cast<float>();
+  F = MF;
+  this->init(V,F,is_static);
+
+  auto min_point = V.colwise().minCoeff();
+  auto max_point = V.colwise().maxCoeff();
+  auto centroid  = (0.5*(min_point + max_point)).eval();
+
+  camera_base_translation.setConstant(0);
+  camera_base_translation.head(centroid.size()) = -centroid.cast<float>();
+  camera_base_zoom = 2.0 / (max_point-min_point).array().abs().maxCoeff();
+}
+
+IGL_INLINE void
+igl::embree::EmbreeRenderer
+::render_buffer(PixelMatrixType& R, PixelMatrixType&G, PixelMatrixType &B,PixelMatrixType &A)
+{
+  assert(R.rows()==G.rows());assert(R.rows()==B.rows());assert(R.rows()==A.rows());
+  assert(R.cols()==G.cols());assert(R.cols()==B.cols());assert(R.cols()==A.cols());
+
+  Eigen::Vector4f viewport(0,0,R.rows(),R.cols());
+
+  float width  = R.rows();
+  float height = R.cols();
+
+  // update view matrix
+  igl::look_at( camera_eye, camera_center, camera_up, view);
+
+  view = view
+    * (rot_matrix * Eigen::Scaling(camera_zoom * camera_base_zoom)
+    * Eigen::Translation3f(camera_translation + camera_base_translation)).matrix();
+  
+  if (orthographic)
+  {
+    float length = (camera_eye - camera_center).norm();
+    float h = tan(camera_view_angle/360.0 * igl::PI) * (length);
+    igl::ortho(-h*width/height, h*width/height, -h, h, camera_dnear, camera_dfar, proj);
+  } else {
+    float fH = tan(camera_view_angle / 360.0 * igl::PI) * camera_dnear;
+    float fW = fH * (double)width/(double)height;
+    igl::frustum(-fW, fW, -fH, fH, camera_dnear, camera_dfar, proj);
+  }
+
+  // go over all pixels in the "view"
+  for(int x=0;x<(int)width;++x) 
+  {
+    for(int y=0;y<(int)height;++y) 
+    {
+      Vec3f s,d,dir;
+      igl::embree::EmbreeRenderer::Hit hit;
+
+      // look into the screen
+      Vec3f win_s(x,y,0);
+      Vec3f win_d(x,y,1);
+      // Source, destination and direction in world
+      igl::unproject(win_s,this->view,this->proj,viewport,s);
+      igl::unproject(win_d,this->view,this->proj,viewport,d);
+      dir = d-s;
+      dir.normalize();
+
+      auto clamp=[](float x)->unsigned char {return (unsigned char)(x<0?0:x>1.0?255:x*255);};
+
+      if(this->intersect_ray(s,dir,hit))
+      {
+        if ( dir.dot(hit.N) > 0.0f)
+        {
+          // TODO: interpolate normals ?
+          hit.N.normalize();
+          // cos between ray and face normal
+          float face_proj=dir.dot(hit.N);
+
+          Eigen::RowVector3f c;
+
+          if(this->uniform_color)
+          {
+            // same color for the whole mesh
+            c=uC;
+          } else if(this->face_based) {
+            // flat color per face
+            c=this->C.row(hit.id);
+          } else { //use barycentric coordinates to interpolate colour
+              c=this->C.row(F(hit.id,1))*hit.u+
+                this->C.row(F(hit.id,2))*hit.v+
+                this->C.row(F(hit.id,0))*(1.0-hit.u-hit.v);
+          }
+
+          R(x,y) = clamp(face_proj*c(0));
+          G(x,y) = clamp(face_proj*c(1));
+          B(x,y) = clamp(face_proj*c(2));
+        }
+        // give the same alpha to all points with something behind
+        A(x,y)=255; 
+      } else {
+        R(x,y)=0;
+        G(x,y)=0;
+        B(x,y)=0;
+        A(x,y)=0;
+      }
+
+    }
+  }
+}
+
+
+IGL_INLINE void
+igl::embree::EmbreeRenderer
+::set_colors(const Eigen::MatrixXd & C)
+{
+  if(C.rows()==V.rows()) // per vertex color
+  {
+    face_based = false;
+    this->C = C.cast<float>();
+    this->uniform_color=false;
+  } else if (C.rows()==F.rows()) {
+    face_based = true;
+    this->C = C.cast<float>();
+    this->uniform_color=false;
+  } else if (C.rows()==1) {
+    face_based = true;
+    this->uC = C.cast<float>();
+    this->uniform_color=true;
+  }else {
+    // don't know what to do
+    this->uniform_color=true;
+    assert(false); //?
+  }
+}
+
+IGL_INLINE void
+igl::embree::EmbreeRenderer
+::set_data(const Eigen::VectorXd & D, igl::ColorMapType cmap)
+{
+  const double caxis_min = D.minCoeff();
+  const double caxis_max = D.maxCoeff();
+  return set_data(D,caxis_min,caxis_max,cmap);
+}
+
+
+IGL_INLINE void igl::embree::EmbreeRenderer::set_data(
+  const Eigen::VectorXd & D,
+  double caxis_min,
+  double caxis_max,
+  igl::ColorMapType cmap)
+{
+    Eigen::MatrixXd C;
+    igl::colormap(cmap,D,caxis_min,caxis_max,C);
+    set_colors(C);
+}
+
+IGL_INLINE void 
+igl::embree::EmbreeRenderer::set_rot(const Eigen::Matrix3d &r)
+{
+  this->rot_matrix = r.cast<float>();
+}
+
+IGL_INLINE void 
+igl::embree::EmbreeRenderer::set_zoom(double zoom)
+{
+  this->camera_zoom=zoom;
+}
+
+IGL_INLINE void 
+igl::embree::EmbreeRenderer::set_translation(const Eigen::Vector3d &tr)
+{
+  this->camera_translation=tr.cast<float>();
+}
+
+IGL_INLINE void 
+igl::embree::EmbreeRenderer::set_face_based(bool _f)
+{
+  this->face_based=_f;
+}
+
+IGL_INLINE void 
+igl::embree::EmbreeRenderer::set_orthographic(bool o)
+{
+  this->orthographic=o;
+}
+
+#ifdef IGL_STATIC_LIBRARY
+#endif //IGL_STATIC_LIBRARY

+ 255 - 0
include/igl/embree/EmbreeRenderer.h

@@ -0,0 +1,255 @@
+// This file is part of libigl, a simple c++ geometry processing library.
+//
+// 
+// Copyright (C) 2020 Vladimir Fonov <[email protected]>
+//               2013 Alec Jacobson <[email protected]>
+//               2014 Christian Schüller <[email protected]>
+//
+// This Source Code Form is subject to the terms of the Mozilla Public License
+// v. 2.0. If a copy of the MPL was not distributed with this file, You can
+// obtain one at http://mozilla.org/MPL/2.0/.
+//
+
+#ifndef IGL_EMBREE_EMBREE_RENDERER_H
+#define IGL_EMBREE_EMBREE_RENDERER_H
+
+#include <igl/colormap.h>
+
+#include <Eigen/Geometry>
+#include <Eigen/Core>
+#include <Eigen/Geometry>
+
+#include <embree3/rtcore.h>
+#include <embree3/rtcore_ray.h>
+#include <iostream>
+#include <vector>
+
+#include "EmbreeDevice.h"
+
+
+namespace igl
+{
+  namespace embree
+  {
+    // embree-based mesh renderer
+    class EmbreeRenderer
+    {
+    public:
+      typedef Eigen::RowVector3f Vec3f;
+
+      struct Hit
+      {
+        int id;    // primitive id
+        int gid;   // geometry id
+        float u,v; // barycentric coordinates
+        float t;   // distance = direction*t to intersection
+        Vec3f N;    // element normal
+      };
+
+      // Initialize embree engine. This will be called on instance `init()`
+      // calls. If already inited then this function does nothing: it is harmless
+      // to call more than once.
+      static IGL_INLINE void global_init();
+    private:
+      // Deinitialize the embree engine.
+      static IGL_INLINE void global_deinit();
+    public:
+      typedef Eigen::Matrix<float,Eigen::Dynamic,3> PointMatrixType;
+      typedef Eigen::Matrix<float,Eigen::Dynamic,3> ColorMatrixType;
+      typedef Eigen::Matrix<int,  Eigen::Dynamic,3> FaceMatrixType;
+      
+      typedef Eigen::Matrix<unsigned char,Eigen::Dynamic,Eigen::Dynamic> PixelMatrixType;
+
+    public:
+      IGL_INLINE EmbreeRenderer();
+    private:
+      // Copying and assignment are not allowed.
+      IGL_INLINE EmbreeRenderer(const EmbreeRenderer & that);
+      IGL_INLINE EmbreeRenderer & operator=(const EmbreeRenderer &);
+    public:
+      virtual inline ~EmbreeRenderer();
+      
+      // Specify mesh, this call reinitializes embree structures
+      // Inputs:
+      //   V  #V x dim matrix of vertex coordinates
+      //   F  #F x simplex_size  matrix of indices of simplex corners into V
+      //   is_static - optimize for static thene (HQ rendering)
+      IGL_INLINE void set_mesh(const Eigen::Matrix<double,Eigen::Dynamic,3> & V,
+                    const Eigen::Matrix<int,  Eigen::Dynamic,3>  & F,
+                    bool is_static=true);
+      // Specify per-vertex or per-face color
+      // Inputs:
+      //   C  #V x 3 matrix of vertex colors
+      //    or #F x 3 matrix of face colors
+      //    or 1 x 3 matrix of uniform color
+      IGL_INLINE void set_colors(const Eigen::MatrixXd & C);
+
+
+      // Use min(D) and max(D) to set caxis.
+      IGL_INLINE void set_data(const Eigen::VectorXd & D,
+                    igl::ColorMapType cmap = igl::COLOR_MAP_TYPE_VIRIDIS);
+  
+      // Specify per-vertex or per-face scalar field
+      //   that will be converted to color using jet color map
+      // Inputs:
+      //   caxis_min  caxis minimum bound
+      //   caxis_max  caxis maximum bound
+      //   D  #V by 1 list of scalar values
+      //   cmap colormap type
+      //   num_steps number of intervals to discretize the colormap
+      IGL_INLINE void set_data(
+        const Eigen::VectorXd & D,
+        double caxis_min,
+        double caxis_max,
+        igl::ColorMapType cmap = igl::COLOR_MAP_TYPE_VIRIDIS);
+
+      // Specify mesh rotation
+      // Inputs:
+      //   r  3 x 3 rotaton matrix
+      IGL_INLINE void set_rot(const Eigen::Matrix3d &r);
+
+      // Specify mesh magnification
+      // Inputs:
+      //   z  magnification ratio
+      IGL_INLINE void set_zoom(double z);
+
+      // Specify mesh translation
+      // Inputs:
+      //   tr  translation vector 
+      IGL_INLINE void set_translation(const Eigen::Vector3d &tr);
+
+      // Specify that color is face based
+      // Inputs:
+      //    f - face or vertex colours
+      IGL_INLINE void set_face_based(bool f);
+
+      // Use orthographic projection
+      // Inputs:
+      //    f - orthographic or perspective projection
+      IGL_INLINE void set_orthographic(bool f );
+
+      // render full buffer
+      // Outputs:
+      //   all outputs should have the same size (size of the output picture)
+      //     area outside of the visible object will have zero alpha component (transparant)
+      //   R - red channel
+      //   G - green channel
+      //   B - blue channel
+      //   A - alpha channel
+      IGL_INLINE void render_buffer(PixelMatrixType &R,
+                         PixelMatrixType &G, 
+                         PixelMatrixType &B,
+                         PixelMatrixType &A);
+
+      // Given a ray find the first hit
+      //
+      // Inputs:
+      //   origin     3d origin point of ray
+      //   direction  3d (not necessarily normalized) direction vector of ray
+      //   tnear      start of ray segment
+      //   tfar       end of ray segment
+      //   mask      a 32 bit mask to identify active geometries.
+      // Output:
+      //   hit        information about hit
+      // Returns true if and only if there was a hit
+      IGL_INLINE bool intersect_ray(
+        const Eigen::RowVector3f& origin,
+        const Eigen::RowVector3f& direction,
+        Hit& hit,
+        float tnear = 0,
+        float tfar = std::numeric_limits<float>::infinity(),
+        int mask = 0xFFFFFFFF) const;
+
+    private:
+
+      // Initialize with a given mesh.
+      //
+      // Inputs:
+      //   V  #V by 3 list of vertex positions
+      //   F  #F by 3 list of Oriented triangles
+      //   isStatic  scene is optimized for static geometry
+      // Side effects:
+      //   The first time this is ever called the embree engine is initialized.
+      IGL_INLINE void init(
+        const PointMatrixType& V,
+        const FaceMatrixType& F,
+        bool isStatic = false);
+
+      // Initialize embree with a given mesh.
+      //
+      // Inputs:
+      //   V  vector of #V by 3 list of vertex positions for each geometry
+      //   F  vector of #F by 3 list of Oriented triangles for each geometry
+      //   masks  a 32 bit mask to identify active geometries.
+      //   isStatic  scene is optimized for static geometry
+      // Side effects:
+      //   The first time this is ever called the embree engine is initialized.
+      IGL_INLINE void init(
+        const std::vector<const PointMatrixType*>& V,
+        const std::vector<const FaceMatrixType*>& F,
+        const std::vector<int>& masks,
+        bool isStatic = false);
+
+
+      // Deinitialize embree datasctructures for current mesh.  Also called on
+      // destruction: no need to call if you just want to init() once and
+      // destroy.
+      IGL_INLINE void deinit();
+      // initialize view parameters
+      IGL_INLINE void init_view();
+
+      // scene data
+      PointMatrixType V; // vertices
+      FaceMatrixType  F; // faces
+      ColorMatrixType C; // colours
+
+      Eigen::RowVector3f uC; // uniform color
+
+      bool face_based;
+      bool uniform_color;
+
+      // Camera parameters
+      float camera_base_zoom;
+      float camera_zoom;
+      
+      Eigen::Vector3f camera_base_translation;
+      Eigen::Vector3f camera_translation;
+      Eigen::Vector3f camera_eye;
+      Eigen::Vector3f camera_up;
+      Eigen::Vector3f camera_center;
+      float camera_view_angle;
+      float camera_dnear;
+      float camera_dfar;
+
+      // projection matrixes      
+      Eigen::Matrix4f view;
+      Eigen::Matrix4f proj;
+      Eigen::Matrix4f norm;
+
+      Eigen::Matrix3f rot_matrix;
+
+      bool orthographic;
+
+      // embree data
+      RTCScene scene;
+      unsigned geomID;
+      bool initialized;
+
+      RTCDevice device;
+
+      IGL_INLINE void create_ray(
+        RTCRayHit& ray,
+        const Eigen::RowVector3f& origin,
+        const Eigen::RowVector3f& direction,
+        float tnear,
+        float tfar,
+        int mask) const;
+
+    };
+  }
+}
+
+#ifndef IGL_STATIC_LIBRARY
+#  include "EmbreeRenderer.cpp"
+#endif
+#endif //IGL_EMBREE_EMBREE_RENDERER_H

+ 451 - 0
include/igl/marching_cubes.cpp

@@ -0,0 +1,451 @@
+#include "marching_cubes.h"
+
+// Adapted from public domain code at
+// http://paulbourke.net/geometry/polygonise/marchingsource.cpp
+
+#include <unordered_map>
+
+template <typename DerivedS, typename DerivedGV, typename DerivedV, typename DerivedF>
+IGL_INLINE void igl::marching_cubes(
+    const Eigen::MatrixBase<DerivedS> &S,
+    const Eigen::MatrixBase<DerivedGV> &GV,
+    const unsigned nx,
+    const unsigned ny,
+    const unsigned nz,
+    const typename DerivedS::Scalar isovalue,
+    Eigen::PlainObjectBase<DerivedV> &V,
+    Eigen::PlainObjectBase<DerivedF> &F)
+{
+  typedef typename DerivedS::Scalar Scalar;
+  typedef typename DerivedF::Scalar Index;
+  // use same order as a2fVertexOffset
+  const unsigned ioffset[8] = {0,1,1+nx,nx,nx*ny,1+nx*ny,1+nx+nx*ny,nx+nx*ny};
+  const int aiCubeEdgeFlags[256]=
+  {
+    0x000, 0x109, 0x203, 0x30a, 0x406, 0x50f, 0x605, 0x70c, 0x80c, 0x905, 0xa0f, 0xb06, 0xc0a, 0xd03, 0xe09, 0xf00, 
+    0x190, 0x099, 0x393, 0x29a, 0x596, 0x49f, 0x795, 0x69c, 0x99c, 0x895, 0xb9f, 0xa96, 0xd9a, 0xc93, 0xf99, 0xe90, 
+    0x230, 0x339, 0x033, 0x13a, 0x636, 0x73f, 0x435, 0x53c, 0xa3c, 0xb35, 0x83f, 0x936, 0xe3a, 0xf33, 0xc39, 0xd30, 
+    0x3a0, 0x2a9, 0x1a3, 0x0aa, 0x7a6, 0x6af, 0x5a5, 0x4ac, 0xbac, 0xaa5, 0x9af, 0x8a6, 0xfaa, 0xea3, 0xda9, 0xca0, 
+    0x460, 0x569, 0x663, 0x76a, 0x066, 0x16f, 0x265, 0x36c, 0xc6c, 0xd65, 0xe6f, 0xf66, 0x86a, 0x963, 0xa69, 0xb60, 
+    0x5f0, 0x4f9, 0x7f3, 0x6fa, 0x1f6, 0x0ff, 0x3f5, 0x2fc, 0xdfc, 0xcf5, 0xfff, 0xef6, 0x9fa, 0x8f3, 0xbf9, 0xaf0, 
+    0x650, 0x759, 0x453, 0x55a, 0x256, 0x35f, 0x055, 0x15c, 0xe5c, 0xf55, 0xc5f, 0xd56, 0xa5a, 0xb53, 0x859, 0x950, 
+    0x7c0, 0x6c9, 0x5c3, 0x4ca, 0x3c6, 0x2cf, 0x1c5, 0x0cc, 0xfcc, 0xec5, 0xdcf, 0xcc6, 0xbca, 0xac3, 0x9c9, 0x8c0, 
+    0x8c0, 0x9c9, 0xac3, 0xbca, 0xcc6, 0xdcf, 0xec5, 0xfcc, 0x0cc, 0x1c5, 0x2cf, 0x3c6, 0x4ca, 0x5c3, 0x6c9, 0x7c0, 
+    0x950, 0x859, 0xb53, 0xa5a, 0xd56, 0xc5f, 0xf55, 0xe5c, 0x15c, 0x055, 0x35f, 0x256, 0x55a, 0x453, 0x759, 0x650, 
+    0xaf0, 0xbf9, 0x8f3, 0x9fa, 0xef6, 0xfff, 0xcf5, 0xdfc, 0x2fc, 0x3f5, 0x0ff, 0x1f6, 0x6fa, 0x7f3, 0x4f9, 0x5f0, 
+    0xb60, 0xa69, 0x963, 0x86a, 0xf66, 0xe6f, 0xd65, 0xc6c, 0x36c, 0x265, 0x16f, 0x066, 0x76a, 0x663, 0x569, 0x460, 
+    0xca0, 0xda9, 0xea3, 0xfaa, 0x8a6, 0x9af, 0xaa5, 0xbac, 0x4ac, 0x5a5, 0x6af, 0x7a6, 0x0aa, 0x1a3, 0x2a9, 0x3a0, 
+    0xd30, 0xc39, 0xf33, 0xe3a, 0x936, 0x83f, 0xb35, 0xa3c, 0x53c, 0x435, 0x73f, 0x636, 0x13a, 0x033, 0x339, 0x230, 
+    0xe90, 0xf99, 0xc93, 0xd9a, 0xa96, 0xb9f, 0x895, 0x99c, 0x69c, 0x795, 0x49f, 0x596, 0x29a, 0x393, 0x099, 0x190, 
+    0xf00, 0xe09, 0xd03, 0xc0a, 0xb06, 0xa0f, 0x905, 0x80c, 0x70c, 0x605, 0x50f, 0x406, 0x30a, 0x203, 0x109, 0x000
+  };
+  //a2eConnection lists the index of the endpoint vertices for each of the 12 edges of the cube
+  const int a2eConnection[12][2] = 
+  {
+    {0,1}, {1,2}, {2,3}, {3,0},
+    {4,5}, {5,6}, {6,7}, {7,4},
+    {0,4}, {1,5}, {2,6}, {3,7}
+  };
+  //  For each of the possible vertex states listed in aiCubeEdgeFlags there is a specific triangulation
+  //  of the edge intersection points.  a2fConnectionTable lists all of them in the form of
+  //  0-5 edge triples with the list terminated by the invalid value -1.
+  //  For example: a2fConnectionTable[3] list the 2 triangles formed when corner[0] 
+  //  and corner[1] are inside of the surface, but the rest of the cube is not.
+  //
+  //  I found this table in an example program someone wrote long ago.  It was probably generated by hand
+  int a2fConnectionTable[256][16] =  
+  {
+    {-1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {0, 8, 3, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {0, 1, 9, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {1, 8, 3, 9, 8, 1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {1, 2, 10, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {0, 8, 3, 1, 2, 10, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {9, 2, 10, 0, 2, 9, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {2, 8, 3, 2, 10, 8, 10, 9, 8, -1, -1, -1, -1, -1, -1, -1},
+    {3, 11, 2, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {0, 11, 2, 8, 11, 0, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {1, 9, 0, 2, 3, 11, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {1, 11, 2, 1, 9, 11, 9, 8, 11, -1, -1, -1, -1, -1, -1, -1},
+    {3, 10, 1, 11, 10, 3, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {0, 10, 1, 0, 8, 10, 8, 11, 10, -1, -1, -1, -1, -1, -1, -1},
+    {3, 9, 0, 3, 11, 9, 11, 10, 9, -1, -1, -1, -1, -1, -1, -1},
+    {9, 8, 10, 10, 8, 11, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {4, 7, 8, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {4, 3, 0, 7, 3, 4, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {0, 1, 9, 8, 4, 7, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {4, 1, 9, 4, 7, 1, 7, 3, 1, -1, -1, -1, -1, -1, -1, -1},
+    {1, 2, 10, 8, 4, 7, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {3, 4, 7, 3, 0, 4, 1, 2, 10, -1, -1, -1, -1, -1, -1, -1},
+    {9, 2, 10, 9, 0, 2, 8, 4, 7, -1, -1, -1, -1, -1, -1, -1},
+    {2, 10, 9, 2, 9, 7, 2, 7, 3, 7, 9, 4, -1, -1, -1, -1},
+    {8, 4, 7, 3, 11, 2, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {11, 4, 7, 11, 2, 4, 2, 0, 4, -1, -1, -1, -1, -1, -1, -1},
+    {9, 0, 1, 8, 4, 7, 2, 3, 11, -1, -1, -1, -1, -1, -1, -1},
+    {4, 7, 11, 9, 4, 11, 9, 11, 2, 9, 2, 1, -1, -1, -1, -1},
+    {3, 10, 1, 3, 11, 10, 7, 8, 4, -1, -1, -1, -1, -1, -1, -1},
+    {1, 11, 10, 1, 4, 11, 1, 0, 4, 7, 11, 4, -1, -1, -1, -1},
+    {4, 7, 8, 9, 0, 11, 9, 11, 10, 11, 0, 3, -1, -1, -1, -1},
+    {4, 7, 11, 4, 11, 9, 9, 11, 10, -1, -1, -1, -1, -1, -1, -1},
+    {9, 5, 4, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {9, 5, 4, 0, 8, 3, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {0, 5, 4, 1, 5, 0, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {8, 5, 4, 8, 3, 5, 3, 1, 5, -1, -1, -1, -1, -1, -1, -1},
+    {1, 2, 10, 9, 5, 4, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {3, 0, 8, 1, 2, 10, 4, 9, 5, -1, -1, -1, -1, -1, -1, -1},
+    {5, 2, 10, 5, 4, 2, 4, 0, 2, -1, -1, -1, -1, -1, -1, -1},
+    {2, 10, 5, 3, 2, 5, 3, 5, 4, 3, 4, 8, -1, -1, -1, -1},
+    {9, 5, 4, 2, 3, 11, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {0, 11, 2, 0, 8, 11, 4, 9, 5, -1, -1, -1, -1, -1, -1, -1},
+    {0, 5, 4, 0, 1, 5, 2, 3, 11, -1, -1, -1, -1, -1, -1, -1},
+    {2, 1, 5, 2, 5, 8, 2, 8, 11, 4, 8, 5, -1, -1, -1, -1},
+    {10, 3, 11, 10, 1, 3, 9, 5, 4, -1, -1, -1, -1, -1, -1, -1},
+    {4, 9, 5, 0, 8, 1, 8, 10, 1, 8, 11, 10, -1, -1, -1, -1},
+    {5, 4, 0, 5, 0, 11, 5, 11, 10, 11, 0, 3, -1, -1, -1, -1},
+    {5, 4, 8, 5, 8, 10, 10, 8, 11, -1, -1, -1, -1, -1, -1, -1},
+    {9, 7, 8, 5, 7, 9, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {9, 3, 0, 9, 5, 3, 5, 7, 3, -1, -1, -1, -1, -1, -1, -1},
+    {0, 7, 8, 0, 1, 7, 1, 5, 7, -1, -1, -1, -1, -1, -1, -1},
+    {1, 5, 3, 3, 5, 7, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {9, 7, 8, 9, 5, 7, 10, 1, 2, -1, -1, -1, -1, -1, -1, -1},
+    {10, 1, 2, 9, 5, 0, 5, 3, 0, 5, 7, 3, -1, -1, -1, -1},
+    {8, 0, 2, 8, 2, 5, 8, 5, 7, 10, 5, 2, -1, -1, -1, -1},
+    {2, 10, 5, 2, 5, 3, 3, 5, 7, -1, -1, -1, -1, -1, -1, -1},
+    {7, 9, 5, 7, 8, 9, 3, 11, 2, -1, -1, -1, -1, -1, -1, -1},
+    {9, 5, 7, 9, 7, 2, 9, 2, 0, 2, 7, 11, -1, -1, -1, -1},
+    {2, 3, 11, 0, 1, 8, 1, 7, 8, 1, 5, 7, -1, -1, -1, -1},
+    {11, 2, 1, 11, 1, 7, 7, 1, 5, -1, -1, -1, -1, -1, -1, -1},
+    {9, 5, 8, 8, 5, 7, 10, 1, 3, 10, 3, 11, -1, -1, -1, -1},
+    {5, 7, 0, 5, 0, 9, 7, 11, 0, 1, 0, 10, 11, 10, 0, -1},
+    {11, 10, 0, 11, 0, 3, 10, 5, 0, 8, 0, 7, 5, 7, 0, -1},
+    {11, 10, 5, 7, 11, 5, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {10, 6, 5, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {0, 8, 3, 5, 10, 6, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {9, 0, 1, 5, 10, 6, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {1, 8, 3, 1, 9, 8, 5, 10, 6, -1, -1, -1, -1, -1, -1, -1},
+    {1, 6, 5, 2, 6, 1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {1, 6, 5, 1, 2, 6, 3, 0, 8, -1, -1, -1, -1, -1, -1, -1},
+    {9, 6, 5, 9, 0, 6, 0, 2, 6, -1, -1, -1, -1, -1, -1, -1},
+    {5, 9, 8, 5, 8, 2, 5, 2, 6, 3, 2, 8, -1, -1, -1, -1},
+    {2, 3, 11, 10, 6, 5, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {11, 0, 8, 11, 2, 0, 10, 6, 5, -1, -1, -1, -1, -1, -1, -1},
+    {0, 1, 9, 2, 3, 11, 5, 10, 6, -1, -1, -1, -1, -1, -1, -1},
+    {5, 10, 6, 1, 9, 2, 9, 11, 2, 9, 8, 11, -1, -1, -1, -1},
+    {6, 3, 11, 6, 5, 3, 5, 1, 3, -1, -1, -1, -1, -1, -1, -1},
+    {0, 8, 11, 0, 11, 5, 0, 5, 1, 5, 11, 6, -1, -1, -1, -1},
+    {3, 11, 6, 0, 3, 6, 0, 6, 5, 0, 5, 9, -1, -1, -1, -1},
+    {6, 5, 9, 6, 9, 11, 11, 9, 8, -1, -1, -1, -1, -1, -1, -1},
+    {5, 10, 6, 4, 7, 8, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {4, 3, 0, 4, 7, 3, 6, 5, 10, -1, -1, -1, -1, -1, -1, -1},
+    {1, 9, 0, 5, 10, 6, 8, 4, 7, -1, -1, -1, -1, -1, -1, -1},
+    {10, 6, 5, 1, 9, 7, 1, 7, 3, 7, 9, 4, -1, -1, -1, -1},
+    {6, 1, 2, 6, 5, 1, 4, 7, 8, -1, -1, -1, -1, -1, -1, -1},
+    {1, 2, 5, 5, 2, 6, 3, 0, 4, 3, 4, 7, -1, -1, -1, -1},
+    {8, 4, 7, 9, 0, 5, 0, 6, 5, 0, 2, 6, -1, -1, -1, -1},
+    {7, 3, 9, 7, 9, 4, 3, 2, 9, 5, 9, 6, 2, 6, 9, -1},
+    {3, 11, 2, 7, 8, 4, 10, 6, 5, -1, -1, -1, -1, -1, -1, -1},
+    {5, 10, 6, 4, 7, 2, 4, 2, 0, 2, 7, 11, -1, -1, -1, -1},
+    {0, 1, 9, 4, 7, 8, 2, 3, 11, 5, 10, 6, -1, -1, -1, -1},
+    {9, 2, 1, 9, 11, 2, 9, 4, 11, 7, 11, 4, 5, 10, 6, -1},
+    {8, 4, 7, 3, 11, 5, 3, 5, 1, 5, 11, 6, -1, -1, -1, -1},
+    {5, 1, 11, 5, 11, 6, 1, 0, 11, 7, 11, 4, 0, 4, 11, -1},
+    {0, 5, 9, 0, 6, 5, 0, 3, 6, 11, 6, 3, 8, 4, 7, -1},
+    {6, 5, 9, 6, 9, 11, 4, 7, 9, 7, 11, 9, -1, -1, -1, -1},
+    {10, 4, 9, 6, 4, 10, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {4, 10, 6, 4, 9, 10, 0, 8, 3, -1, -1, -1, -1, -1, -1, -1},
+    {10, 0, 1, 10, 6, 0, 6, 4, 0, -1, -1, -1, -1, -1, -1, -1},
+    {8, 3, 1, 8, 1, 6, 8, 6, 4, 6, 1, 10, -1, -1, -1, -1},
+    {1, 4, 9, 1, 2, 4, 2, 6, 4, -1, -1, -1, -1, -1, -1, -1},
+    {3, 0, 8, 1, 2, 9, 2, 4, 9, 2, 6, 4, -1, -1, -1, -1},
+    {0, 2, 4, 4, 2, 6, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {8, 3, 2, 8, 2, 4, 4, 2, 6, -1, -1, -1, -1, -1, -1, -1},
+    {10, 4, 9, 10, 6, 4, 11, 2, 3, -1, -1, -1, -1, -1, -1, -1},
+    {0, 8, 2, 2, 8, 11, 4, 9, 10, 4, 10, 6, -1, -1, -1, -1},
+    {3, 11, 2, 0, 1, 6, 0, 6, 4, 6, 1, 10, -1, -1, -1, -1},
+    {6, 4, 1, 6, 1, 10, 4, 8, 1, 2, 1, 11, 8, 11, 1, -1},
+    {9, 6, 4, 9, 3, 6, 9, 1, 3, 11, 6, 3, -1, -1, -1, -1},
+    {8, 11, 1, 8, 1, 0, 11, 6, 1, 9, 1, 4, 6, 4, 1, -1},
+    {3, 11, 6, 3, 6, 0, 0, 6, 4, -1, -1, -1, -1, -1, -1, -1},
+    {6, 4, 8, 11, 6, 8, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {7, 10, 6, 7, 8, 10, 8, 9, 10, -1, -1, -1, -1, -1, -1, -1},
+    {0, 7, 3, 0, 10, 7, 0, 9, 10, 6, 7, 10, -1, -1, -1, -1},
+    {10, 6, 7, 1, 10, 7, 1, 7, 8, 1, 8, 0, -1, -1, -1, -1},
+    {10, 6, 7, 10, 7, 1, 1, 7, 3, -1, -1, -1, -1, -1, -1, -1},
+    {1, 2, 6, 1, 6, 8, 1, 8, 9, 8, 6, 7, -1, -1, -1, -1},
+    {2, 6, 9, 2, 9, 1, 6, 7, 9, 0, 9, 3, 7, 3, 9, -1},
+    {7, 8, 0, 7, 0, 6, 6, 0, 2, -1, -1, -1, -1, -1, -1, -1},
+    {7, 3, 2, 6, 7, 2, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {2, 3, 11, 10, 6, 8, 10, 8, 9, 8, 6, 7, -1, -1, -1, -1},
+    {2, 0, 7, 2, 7, 11, 0, 9, 7, 6, 7, 10, 9, 10, 7, -1},
+    {1, 8, 0, 1, 7, 8, 1, 10, 7, 6, 7, 10, 2, 3, 11, -1},
+    {11, 2, 1, 11, 1, 7, 10, 6, 1, 6, 7, 1, -1, -1, -1, -1},
+    {8, 9, 6, 8, 6, 7, 9, 1, 6, 11, 6, 3, 1, 3, 6, -1},
+    {0, 9, 1, 11, 6, 7, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {7, 8, 0, 7, 0, 6, 3, 11, 0, 11, 6, 0, -1, -1, -1, -1},
+    {7, 11, 6, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {7, 6, 11, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {3, 0, 8, 11, 7, 6, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {0, 1, 9, 11, 7, 6, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {8, 1, 9, 8, 3, 1, 11, 7, 6, -1, -1, -1, -1, -1, -1, -1},
+    {10, 1, 2, 6, 11, 7, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {1, 2, 10, 3, 0, 8, 6, 11, 7, -1, -1, -1, -1, -1, -1, -1},
+    {2, 9, 0, 2, 10, 9, 6, 11, 7, -1, -1, -1, -1, -1, -1, -1},
+    {6, 11, 7, 2, 10, 3, 10, 8, 3, 10, 9, 8, -1, -1, -1, -1},
+    {7, 2, 3, 6, 2, 7, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {7, 0, 8, 7, 6, 0, 6, 2, 0, -1, -1, -1, -1, -1, -1, -1},
+    {2, 7, 6, 2, 3, 7, 0, 1, 9, -1, -1, -1, -1, -1, -1, -1},
+    {1, 6, 2, 1, 8, 6, 1, 9, 8, 8, 7, 6, -1, -1, -1, -1},
+    {10, 7, 6, 10, 1, 7, 1, 3, 7, -1, -1, -1, -1, -1, -1, -1},
+    {10, 7, 6, 1, 7, 10, 1, 8, 7, 1, 0, 8, -1, -1, -1, -1},
+    {0, 3, 7, 0, 7, 10, 0, 10, 9, 6, 10, 7, -1, -1, -1, -1},
+    {7, 6, 10, 7, 10, 8, 8, 10, 9, -1, -1, -1, -1, -1, -1, -1},
+    {6, 8, 4, 11, 8, 6, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {3, 6, 11, 3, 0, 6, 0, 4, 6, -1, -1, -1, -1, -1, -1, -1},
+    {8, 6, 11, 8, 4, 6, 9, 0, 1, -1, -1, -1, -1, -1, -1, -1},
+    {9, 4, 6, 9, 6, 3, 9, 3, 1, 11, 3, 6, -1, -1, -1, -1},
+    {6, 8, 4, 6, 11, 8, 2, 10, 1, -1, -1, -1, -1, -1, -1, -1},
+    {1, 2, 10, 3, 0, 11, 0, 6, 11, 0, 4, 6, -1, -1, -1, -1},
+    {4, 11, 8, 4, 6, 11, 0, 2, 9, 2, 10, 9, -1, -1, -1, -1},
+    {10, 9, 3, 10, 3, 2, 9, 4, 3, 11, 3, 6, 4, 6, 3, -1},
+    {8, 2, 3, 8, 4, 2, 4, 6, 2, -1, -1, -1, -1, -1, -1, -1},
+    {0, 4, 2, 4, 6, 2, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {1, 9, 0, 2, 3, 4, 2, 4, 6, 4, 3, 8, -1, -1, -1, -1},
+    {1, 9, 4, 1, 4, 2, 2, 4, 6, -1, -1, -1, -1, -1, -1, -1},
+    {8, 1, 3, 8, 6, 1, 8, 4, 6, 6, 10, 1, -1, -1, -1, -1},
+    {10, 1, 0, 10, 0, 6, 6, 0, 4, -1, -1, -1, -1, -1, -1, -1},
+    {4, 6, 3, 4, 3, 8, 6, 10, 3, 0, 3, 9, 10, 9, 3, -1},
+    {10, 9, 4, 6, 10, 4, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {4, 9, 5, 7, 6, 11, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {0, 8, 3, 4, 9, 5, 11, 7, 6, -1, -1, -1, -1, -1, -1, -1},
+    {5, 0, 1, 5, 4, 0, 7, 6, 11, -1, -1, -1, -1, -1, -1, -1},
+    {11, 7, 6, 8, 3, 4, 3, 5, 4, 3, 1, 5, -1, -1, -1, -1},
+    {9, 5, 4, 10, 1, 2, 7, 6, 11, -1, -1, -1, -1, -1, -1, -1},
+    {6, 11, 7, 1, 2, 10, 0, 8, 3, 4, 9, 5, -1, -1, -1, -1},
+    {7, 6, 11, 5, 4, 10, 4, 2, 10, 4, 0, 2, -1, -1, -1, -1},
+    {3, 4, 8, 3, 5, 4, 3, 2, 5, 10, 5, 2, 11, 7, 6, -1},
+    {7, 2, 3, 7, 6, 2, 5, 4, 9, -1, -1, -1, -1, -1, -1, -1},
+    {9, 5, 4, 0, 8, 6, 0, 6, 2, 6, 8, 7, -1, -1, -1, -1},
+    {3, 6, 2, 3, 7, 6, 1, 5, 0, 5, 4, 0, -1, -1, -1, -1},
+    {6, 2, 8, 6, 8, 7, 2, 1, 8, 4, 8, 5, 1, 5, 8, -1},
+    {9, 5, 4, 10, 1, 6, 1, 7, 6, 1, 3, 7, -1, -1, -1, -1},
+    {1, 6, 10, 1, 7, 6, 1, 0, 7, 8, 7, 0, 9, 5, 4, -1},
+    {4, 0, 10, 4, 10, 5, 0, 3, 10, 6, 10, 7, 3, 7, 10, -1},
+    {7, 6, 10, 7, 10, 8, 5, 4, 10, 4, 8, 10, -1, -1, -1, -1},
+    {6, 9, 5, 6, 11, 9, 11, 8, 9, -1, -1, -1, -1, -1, -1, -1},
+    {3, 6, 11, 0, 6, 3, 0, 5, 6, 0, 9, 5, -1, -1, -1, -1},
+    {0, 11, 8, 0, 5, 11, 0, 1, 5, 5, 6, 11, -1, -1, -1, -1},
+    {6, 11, 3, 6, 3, 5, 5, 3, 1, -1, -1, -1, -1, -1, -1, -1},
+    {1, 2, 10, 9, 5, 11, 9, 11, 8, 11, 5, 6, -1, -1, -1, -1},
+    {0, 11, 3, 0, 6, 11, 0, 9, 6, 5, 6, 9, 1, 2, 10, -1},
+    {11, 8, 5, 11, 5, 6, 8, 0, 5, 10, 5, 2, 0, 2, 5, -1},
+    {6, 11, 3, 6, 3, 5, 2, 10, 3, 10, 5, 3, -1, -1, -1, -1},
+    {5, 8, 9, 5, 2, 8, 5, 6, 2, 3, 8, 2, -1, -1, -1, -1},
+    {9, 5, 6, 9, 6, 0, 0, 6, 2, -1, -1, -1, -1, -1, -1, -1},
+    {1, 5, 8, 1, 8, 0, 5, 6, 8, 3, 8, 2, 6, 2, 8, -1},
+    {1, 5, 6, 2, 1, 6, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {1, 3, 6, 1, 6, 10, 3, 8, 6, 5, 6, 9, 8, 9, 6, -1},
+    {10, 1, 0, 10, 0, 6, 9, 5, 0, 5, 6, 0, -1, -1, -1, -1},
+    {0, 3, 8, 5, 6, 10, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {10, 5, 6, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {11, 5, 10, 7, 5, 11, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {11, 5, 10, 11, 7, 5, 8, 3, 0, -1, -1, -1, -1, -1, -1, -1},
+    {5, 11, 7, 5, 10, 11, 1, 9, 0, -1, -1, -1, -1, -1, -1, -1},
+    {10, 7, 5, 10, 11, 7, 9, 8, 1, 8, 3, 1, -1, -1, -1, -1},
+    {11, 1, 2, 11, 7, 1, 7, 5, 1, -1, -1, -1, -1, -1, -1, -1},
+    {0, 8, 3, 1, 2, 7, 1, 7, 5, 7, 2, 11, -1, -1, -1, -1},
+    {9, 7, 5, 9, 2, 7, 9, 0, 2, 2, 11, 7, -1, -1, -1, -1},
+    {7, 5, 2, 7, 2, 11, 5, 9, 2, 3, 2, 8, 9, 8, 2, -1},
+    {2, 5, 10, 2, 3, 5, 3, 7, 5, -1, -1, -1, -1, -1, -1, -1},
+    {8, 2, 0, 8, 5, 2, 8, 7, 5, 10, 2, 5, -1, -1, -1, -1},
+    {9, 0, 1, 5, 10, 3, 5, 3, 7, 3, 10, 2, -1, -1, -1, -1},
+    {9, 8, 2, 9, 2, 1, 8, 7, 2, 10, 2, 5, 7, 5, 2, -1},
+    {1, 3, 5, 3, 7, 5, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {0, 8, 7, 0, 7, 1, 1, 7, 5, -1, -1, -1, -1, -1, -1, -1},
+    {9, 0, 3, 9, 3, 5, 5, 3, 7, -1, -1, -1, -1, -1, -1, -1},
+    {9, 8, 7, 5, 9, 7, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {5, 8, 4, 5, 10, 8, 10, 11, 8, -1, -1, -1, -1, -1, -1, -1},
+    {5, 0, 4, 5, 11, 0, 5, 10, 11, 11, 3, 0, -1, -1, -1, -1},
+    {0, 1, 9, 8, 4, 10, 8, 10, 11, 10, 4, 5, -1, -1, -1, -1},
+    {10, 11, 4, 10, 4, 5, 11, 3, 4, 9, 4, 1, 3, 1, 4, -1},
+    {2, 5, 1, 2, 8, 5, 2, 11, 8, 4, 5, 8, -1, -1, -1, -1},
+    {0, 4, 11, 0, 11, 3, 4, 5, 11, 2, 11, 1, 5, 1, 11, -1},
+    {0, 2, 5, 0, 5, 9, 2, 11, 5, 4, 5, 8, 11, 8, 5, -1},
+    {9, 4, 5, 2, 11, 3, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {2, 5, 10, 3, 5, 2, 3, 4, 5, 3, 8, 4, -1, -1, -1, -1},
+    {5, 10, 2, 5, 2, 4, 4, 2, 0, -1, -1, -1, -1, -1, -1, -1},
+    {3, 10, 2, 3, 5, 10, 3, 8, 5, 4, 5, 8, 0, 1, 9, -1},
+    {5, 10, 2, 5, 2, 4, 1, 9, 2, 9, 4, 2, -1, -1, -1, -1},
+    {8, 4, 5, 8, 5, 3, 3, 5, 1, -1, -1, -1, -1, -1, -1, -1},
+    {0, 4, 5, 1, 0, 5, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {8, 4, 5, 8, 5, 3, 9, 0, 5, 0, 3, 5, -1, -1, -1, -1},
+    {9, 4, 5, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {4, 11, 7, 4, 9, 11, 9, 10, 11, -1, -1, -1, -1, -1, -1, -1},
+    {0, 8, 3, 4, 9, 7, 9, 11, 7, 9, 10, 11, -1, -1, -1, -1},
+    {1, 10, 11, 1, 11, 4, 1, 4, 0, 7, 4, 11, -1, -1, -1, -1},
+    {3, 1, 4, 3, 4, 8, 1, 10, 4, 7, 4, 11, 10, 11, 4, -1},
+    {4, 11, 7, 9, 11, 4, 9, 2, 11, 9, 1, 2, -1, -1, -1, -1},
+    {9, 7, 4, 9, 11, 7, 9, 1, 11, 2, 11, 1, 0, 8, 3, -1},
+    {11, 7, 4, 11, 4, 2, 2, 4, 0, -1, -1, -1, -1, -1, -1, -1},
+    {11, 7, 4, 11, 4, 2, 8, 3, 4, 3, 2, 4, -1, -1, -1, -1},
+    {2, 9, 10, 2, 7, 9, 2, 3, 7, 7, 4, 9, -1, -1, -1, -1},
+    {9, 10, 7, 9, 7, 4, 10, 2, 7, 8, 7, 0, 2, 0, 7, -1},
+    {3, 7, 10, 3, 10, 2, 7, 4, 10, 1, 10, 0, 4, 0, 10, -1},
+    {1, 10, 2, 8, 7, 4, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {4, 9, 1, 4, 1, 7, 7, 1, 3, -1, -1, -1, -1, -1, -1, -1},
+    {4, 9, 1, 4, 1, 7, 0, 8, 1, 8, 7, 1, -1, -1, -1, -1},
+    {4, 0, 3, 7, 4, 3, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {4, 8, 7, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {9, 10, 8, 10, 11, 8, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {3, 0, 9, 3, 9, 11, 11, 9, 10, -1, -1, -1, -1, -1, -1, -1},
+    {0, 1, 10, 0, 10, 8, 8, 10, 11, -1, -1, -1, -1, -1, -1, -1},
+    {3, 1, 10, 11, 3, 10, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {1, 2, 11, 1, 11, 9, 9, 11, 8, -1, -1, -1, -1, -1, -1, -1},
+    {3, 0, 9, 3, 9, 11, 1, 2, 9, 2, 11, 9, -1, -1, -1, -1},
+    {0, 2, 11, 8, 0, 11, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {3, 2, 11, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {2, 3, 8, 2, 8, 10, 10, 8, 9, -1, -1, -1, -1, -1, -1, -1},
+    {9, 10, 2, 0, 9, 2, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {2, 3, 8, 2, 8, 10, 0, 1, 8, 1, 10, 8, -1, -1, -1, -1},
+    {1, 10, 2, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {1, 3, 8, 9, 1, 8, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {0, 9, 1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {0, 3, 8, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1},
+    {-1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}
+  };
+
+
+  std::unordered_map<int64_t,int> E2V;
+  V.resize(std::pow(nx*ny*nz,2./3.),3);
+  F.resize(std::pow(nx*ny*nz,2./3.),3);
+  int n = 0;
+  int m = 0;
+
+  const auto xyz2i = [&nx,&ny,&nz]
+    (const int & x, const int & y, const int & z)->unsigned
+  {
+    return x+nx*(y+ny*(z));
+  };
+  const auto ij2key = [](int32_t i,int32_t j)
+  {
+    if(i>j){ std::swap(i,j); }
+    std::int64_t ret = 0;
+    ret |= i;
+    ret |= static_cast<std::int64_t>(j) << 32;
+    return ret;
+  };
+  const auto ij2vertex = [&E2V,&V,&n,&GV,&ij2key]
+    (const unsigned & i, const unsigned & j, const Scalar & t)
+  {
+    const auto key = ij2key(i,j);
+    const auto it = E2V.find(key);
+    int v = -1;
+    if(it == E2V.end())
+    {
+      // new vertex
+      if(n==V.rows()){ V.conservativeResize(V.rows()*2+1,V.cols()); }
+      V.row(n) = GV.row(i) + t*(GV.row(j) - GV.row(i));
+      v = n;
+      E2V[key] = v;
+      n++;
+    }else
+    {
+      v = it->second;
+    }
+    return v;
+  };
+  //fGetOffset finds the approximate point of intersection of the surface
+  // between two points with the values fValue1 and fValue2
+  const auto inv_lerp = [&isovalue](const Scalar & a, const Scalar & b)->Scalar
+  {
+    const Scalar delta = b-a;
+    if(delta == 0) { return 0.5; }
+    return (isovalue - a)/delta;
+  };
+  const auto cube = 
+    [
+      &S,&V,&n,&F,&m,&isovalue,
+      &E2V,&ij2vertex,&xyz2i,&inv_lerp,&ioffset,
+      &aiCubeEdgeFlags,&a2eConnection,a2fConnectionTable
+    ]
+    (const int x, const int y, const int z)
+  {
+    const unsigned i = xyz2i(x,y,z);
+
+    //Make a local copy of the values at the cube's corners
+    static Eigen::Matrix<Scalar,8,1> cS;
+    static Eigen::Matrix<unsigned,8,1> cI;
+    //Find which vertices are inside of the surface and which are outside
+    int c_flags = 0;
+    for(int c = 0; c < 8; c++)
+    {
+      const unsigned ic = i + ioffset[c];
+      cI(c) = ic;
+      cS(c) = S(ic);
+      if(cS(c) > isovalue){ c_flags |= 1<<c; }
+    }
+    //Find which edges are intersected by the surface
+    int e_flags = aiCubeEdgeFlags[c_flags];
+    //If the cube is entirely inside or outside of the surface, then there will be no intersections
+    if(e_flags == 0) { return; }
+    //Find the point of intersection of the surface with each edge
+    //Then find the normal to the surface at those points
+    Eigen::Matrix<Index,12,1> edge_vertices;
+    for(int e = 0; e < 12; e++)
+    {
+#ifndef NDEBUG
+      edge_vertices[e] = -1;
+#endif
+      //if there is an intersection on this edge
+      if(e_flags & (1<<e))
+      {
+        // find crossing point assuming linear interpolation along edges
+        const Scalar t = 
+          inv_lerp(cS(a2eConnection[e][0]),cS(a2eConnection[e][1]));
+        // record global index into local table
+        edge_vertices[e] = 
+          ij2vertex(cI(a2eConnection[e][0]),cI(a2eConnection[e][1]),t);
+        assert(edge_vertices[e] >= 0);
+        assert(edge_vertices[e] < n);
+      }
+    }
+    // Insert the triangles that were found.  There can be up to five per cube
+    for(int f = 0; f < 5; f++)
+    {
+      if(a2fConnectionTable[c_flags][3*f] < 0) break;
+      if(m==F.rows()){ F.conservativeResize(F.rows()*2+1,F.cols()); }
+      assert(edge_vertices[a2fConnectionTable[c_flags][3*f+0]]>=0);
+      assert(edge_vertices[a2fConnectionTable[c_flags][3*f+1]]>=0);
+      assert(edge_vertices[a2fConnectionTable[c_flags][3*f+2]]>=0);
+      F.row(m) <<
+        edge_vertices[a2fConnectionTable[c_flags][3*f+0]],
+        edge_vertices[a2fConnectionTable[c_flags][3*f+1]],
+        edge_vertices[a2fConnectionTable[c_flags][3*f+2]];
+      m++;
+    }
+  };
+
+  // march over all cubes (loop order chosen to match memory)
+  //
+  // Should be possible to parallelize safely if threads a "well separated".
+  // Like red-black Gauss Seidel. Probably each thread need's their own E2V,V,F,
+  // and then merge at the end. Annoying part are the edges lying on the
+  // interface between chunks.
+  for(int z=0;z<nz-1;z++)
+  {
+    for(int y=0;y<ny-1;y++)
+    {
+      for(int x=0;x<nx-1;x++)
+      {
+        cube(x,y,z);
+      }
+    }
+  }
+  V.conservativeResize(n,3);
+  F.conservativeResize(m,3);
+}
+
+#ifdef IGL_STATIC_LIBRARY
+// Explicit template instantiation
+// generated by autoexplicit.sh
+template void igl::marching_cubes<Eigen::Matrix<double, -1, 1, 0, -1, 1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<int, -1, -1, 0, -1, -1> >(Eigen::MatrixBase<Eigen::Matrix<double, -1, 1, 0, -1, 1> > const&, Eigen::MatrixBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> > const&, unsigned int, unsigned int, unsigned int, Eigen::Matrix<double, -1, 1, 0, -1, 1>::Scalar, Eigen::PlainObjectBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> >&, Eigen::PlainObjectBase<Eigen::Matrix<int, -1, -1, 0, -1, -1> >&);
+#endif

+ 52 - 0
include/igl/marching_cubes.h

@@ -0,0 +1,52 @@
+// This file is part of libigl, a simple c++ geometry processing library.
+//
+// Copyright (C) 2014 Alec Jacobson <[email protected]>
+//
+// This Source Code Form is subject to the terms of the Mozilla Public License
+// v. 2.0. If a copy of the MPL was not distributed with this file, You can
+// obtain one at http://mozilla.org/MPL/2.0/.
+#ifndef IGL_MARCHING_CUBES_H
+#define IGL_MARCHING_CUBES_H
+#include "igl_inline.h"
+
+#include <Eigen/Core>
+namespace igl
+{
+  // marching_cubes( values, points, x_res, y_res, z_res, isovalue, vertices, faces )
+  //
+  // performs marching cubes reconstruction on a grid defined by values, and
+  // points, and generates a mesh defined by vertices and faces
+  //
+  // Input:
+  //   S   nx*ny*nz list of values at each grid corner
+  //       i.e. S(x + y*xres + z*xres*yres) for corner (x,y,z)
+  //   GV  nx*ny*nz by 3 array of corresponding grid corner vertex locations
+  //   nx  resolutions of the grid in x dimension
+  //   ny  resolutions of the grid in y dimension
+  //   nz  resolutions of the grid in z dimension
+  //   isovalue  the isovalue of the surface to reconstruct
+  // Output:
+  //   V  #V by 3 list of mesh vertex positions
+  //   F  #F by 3 list of mesh triangle indices into rows of V
+  //
+  template <
+    typename DerivedS, 
+    typename DerivedGV, 
+    typename DerivedV, 
+    typename DerivedF>
+  IGL_INLINE void marching_cubes(
+    const Eigen::MatrixBase<DerivedS> & S,
+    const Eigen::MatrixBase<DerivedGV> & GV,
+    const unsigned nx,
+    const unsigned ny,
+    const unsigned nz,
+    const typename DerivedS::Scalar isovalue,
+    Eigen::PlainObjectBase<DerivedV> &V,
+    Eigen::PlainObjectBase<DerivedF> &F);
+}
+
+#ifndef IGL_STATIC_LIBRARY
+#  include "marching_cubes.cpp"
+#endif
+
+#endif

+ 55 - 0
include/igl/offset_surface.cpp

@@ -0,0 +1,55 @@
+#include "offset_surface.h"
+#include "marching_cubes.h"
+#include "voxel_grid.h"
+#include "signed_distance.h"
+#include "flood_fill.h"
+#include <cassert>
+
+template <
+  typename DerivedV,
+  typename DerivedF,
+  typename isolevelType,
+  typename DerivedSV,
+  typename DerivedSF,
+  typename DerivedGV,
+  typename Derivedside,
+  typename DerivedS>
+void igl::offset_surface(
+  const Eigen::MatrixBase<DerivedV> & V,
+  const Eigen::MatrixBase<DerivedF> & F,
+  const isolevelType isolevel,
+  const typename Derivedside::Scalar s,
+  const SignedDistanceType & signed_distance_type,
+  Eigen::PlainObjectBase<DerivedSV> & SV,
+  Eigen::PlainObjectBase<DerivedSF> & SF,
+  Eigen::PlainObjectBase<DerivedGV> &   GV,
+  Eigen::PlainObjectBase<Derivedside> & side,
+  Eigen::PlainObjectBase<DerivedS> & S)
+{
+  typedef typename DerivedV::Scalar Scalar;
+  typedef typename DerivedF::Scalar Index;
+  igl::voxel_grid(V,isolevel,s,1,GV,side);
+
+  const Scalar h = 
+    (GV.col(0).maxCoeff()-GV.col(0).minCoeff())/((Scalar)(side(0)-1));
+  const Scalar lower_bound = isolevel-sqrt(3.0)*h;
+  const Scalar upper_bound = isolevel+sqrt(3.0)*h;
+  {
+    Eigen::Matrix<Index,Eigen::Dynamic,1> I;
+    Eigen::Matrix<typename DerivedV::Scalar,Eigen::Dynamic,3> C,N;
+    igl::signed_distance(
+      GV,V,F,signed_distance_type,lower_bound,upper_bound,S,I,C,N);
+  }
+  igl::flood_fill(side,S);
+  
+  DerivedS SS = S.array()-isolevel;
+  igl::marching_cubes(SS,GV,side(0),side(1),side(2),0,SV,SF);
+}
+
+#ifdef IGL_STATIC_LIBRARY
+// Explicit template instantiation
+// generated by autoexplicit.sh
+template void igl::offset_surface<Eigen::Matrix<double, -1, 3, 1, -1, 3>, Eigen::Matrix<int, -1, 3, 1, -1, 3>, double, Eigen::Matrix<double, -1, 3, 1, -1, 3>, Eigen::Matrix<int, -1, 3, 1, -1, 3>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<int, 1, 3, 1, 1, 3>, Eigen::Matrix<double, -1, 1, 0, -1, 1> >(Eigen::MatrixBase<Eigen::Matrix<double, -1, 3, 1, -1, 3> > const&, Eigen::MatrixBase<Eigen::Matrix<int, -1, 3, 1, -1, 3> > const&, double, Eigen::Matrix<int, 1, 3, 1, 1, 3>::Scalar, igl::SignedDistanceType const&, Eigen::PlainObjectBase<Eigen::Matrix<double, -1, 3, 1, -1, 3> >&, Eigen::PlainObjectBase<Eigen::Matrix<int, -1, 3, 1, -1, 3> >&, Eigen::PlainObjectBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> >&, Eigen::PlainObjectBase<Eigen::Matrix<int, 1, 3, 1, 1, 3> >&, Eigen::PlainObjectBase<Eigen::Matrix<double, -1, 1, 0, -1, 1> >&);
+template void igl::offset_surface<Eigen::Matrix<float, -1, 3, 1, -1, 3>, Eigen::Matrix<int, -1, 3, 1, -1, 3>, float, Eigen::Matrix<float, -1, 3, 1, -1, 3>, Eigen::Matrix<int, -1, 3, 1, -1, 3>, Eigen::Matrix<float, -1, -1, 0, -1, -1>, Eigen::Matrix<int, 1, 3, 1, 1, 3>, Eigen::Matrix<float, -1, 1, 0, -1, 1> >(Eigen::MatrixBase<Eigen::Matrix<float, -1, 3, 1, -1, 3> > const&, Eigen::MatrixBase<Eigen::Matrix<int, -1, 3, 1, -1, 3> > const&, float, Eigen::Matrix<int, 1, 3, 1, 1, 3>::Scalar, igl::SignedDistanceType const&, Eigen::PlainObjectBase<Eigen::Matrix<float, -1, 3, 1, -1, 3> >&, Eigen::PlainObjectBase<Eigen::Matrix<int, -1, 3, 1, -1, 3> >&, Eigen::PlainObjectBase<Eigen::Matrix<float, -1, -1, 0, -1, -1> >&, Eigen::PlainObjectBase<Eigen::Matrix<int, 1, 3, 1, 1, 3> >&, Eigen::PlainObjectBase<Eigen::Matrix<float, -1, 1, 0, -1, 1> >&);
+template void igl::offset_surface<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<int, -1, -1, 0, -1, -1>, double, Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<int, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<int, 1, 3, 1, 1, 3>, Eigen::Matrix<double, -1, 1, 0, -1, 1> >(Eigen::MatrixBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> > const&, Eigen::MatrixBase<Eigen::Matrix<int, -1, -1, 0, -1, -1> > const&, double, Eigen::Matrix<int, 1, 3, 1, 1, 3>::Scalar, igl::SignedDistanceType const&, Eigen::PlainObjectBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> >&, Eigen::PlainObjectBase<Eigen::Matrix<int, -1, -1, 0, -1, -1> >&, Eigen::PlainObjectBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> >&, Eigen::PlainObjectBase<Eigen::Matrix<int, 1, 3, 1, 1, 3> >&, Eigen::PlainObjectBase<Eigen::Matrix<double, -1, 1, 0, -1, 1> >&);
+#endif

+ 52 - 0
include/igl/offset_surface.h

@@ -0,0 +1,52 @@
+#ifndef IGL_OFFSET_SURFACE_H
+#define IGL_OFFSET_SURFACE_H
+#include "igl_inline.h"
+#include "signed_distance.h"
+#include <Eigen/Core>
+
+namespace igl
+{
+  // Compute a triangulated offset surface using matching cubes on a grid of
+  // signed distance values from the input triangle mesh.
+  //
+  // Inputs:
+  //   V  #V by 3 list of mesh vertex positions
+  //   F  #F by 3 list of mesh triangle indices into V
+  //   isolevel  iso level to extract (signed distance: negative inside)
+  //   s  number of grid cells along longest side (controls resolution)
+  //   signed_distance_type  type of signing to use (see
+  //     ../signed_distance.h)
+  // Outputs:
+  //   SV  #SV by 3 list of output surface mesh vertex positions
+  //   SF  #SF by 3 list of output mesh triangle indices into SV
+  //   GV  #GV=side(0)*side(1)*side(2) by 3 list of grid cell centers
+  //   side  list of number of grid cells in x, y, and z directions
+  //   S  #GV by 3 list of signed distance values _near_ `isolevel` ("far"
+  //     from `isolevel` these values are incorrect)
+  //
+  template <
+    typename DerivedV,
+    typename DerivedF,
+    typename isolevelType,
+    typename DerivedSV,
+    typename DerivedSF,
+    typename DerivedGV,
+    typename Derivedside,
+    typename DerivedS>
+  void offset_surface(
+    const Eigen::MatrixBase<DerivedV> & V,
+    const Eigen::MatrixBase<DerivedF> & F,
+    const isolevelType isolevel,
+    const typename Derivedside::Scalar s,
+    const SignedDistanceType & signed_distance_type,
+    Eigen::PlainObjectBase<DerivedSV> & SV,
+    Eigen::PlainObjectBase<DerivedSF> & SF,
+    Eigen::PlainObjectBase<DerivedGV> & GV,
+    Eigen::PlainObjectBase<Derivedside> & side,
+    Eigen::PlainObjectBase<DerivedS> & S);
+  
+}
+#ifndef IGL_STATIC_LIBRARY
+#  include "offset_surface.cpp"
+#endif 
+#endif 

+ 2 - 0
include/igl/per_edge_normals.cpp

@@ -74,6 +74,8 @@ IGL_INLINE void igl::per_edge_normals(
       }
     }
   }
+  // take average via normalization
+  N.rowwise().normalize();
 }
 
 template <

+ 5 - 6
include/igl/copyleft/swept_volume.cpp → include/igl/swept_volume.cpp

@@ -1,11 +1,11 @@
 #include "swept_volume.h"
-#include "../swept_volume_bounding_box.h"
-#include "../swept_volume_signed_distance.h"
-#include "../voxel_grid.h"
+#include "swept_volume_bounding_box.h"
+#include "swept_volume_signed_distance.h"
+#include "voxel_grid.h"
 #include "marching_cubes.h"
 #include <iostream>
 
-IGL_INLINE void igl::copyleft::swept_volume(
+IGL_INLINE void igl::swept_volume(
   const Eigen::MatrixXd & V,
   const Eigen::MatrixXi & F,
   const std::function<Eigen::Affine3d(const double t)> & transform,
@@ -18,7 +18,6 @@ IGL_INLINE void igl::copyleft::swept_volume(
   using namespace std;
   using namespace Eigen;
   using namespace igl;
-  using namespace igl::copyleft;
 
   const auto & Vtransform = 
     [&V,&transform](const size_t vi,const double t)->RowVector3d
@@ -45,5 +44,5 @@ IGL_INLINE void igl::copyleft::swept_volume(
   VectorXd S;
   swept_volume_signed_distance(V,F,transform,steps,GV,res,h,isolevel,S);
   S.array()-=isolevel;
-  marching_cubes(S,GV,res(0),res(1),res(2),SV,SF);
+  marching_cubes(S,GV,res(0),res(1),res(2),0,SV,SF);
 }

+ 39 - 0
include/igl/swept_volume.h

@@ -0,0 +1,39 @@
+#ifndef IGL_SWEPT_VOLUME_H
+#define IGL_SWEPT_VOLUME_H
+#include "igl_inline.h"
+#include <Eigen/Core>
+#include <Eigen/Geometry>
+namespace igl
+{
+  // Compute the surface of the swept volume of a solid object with surface
+  // (V,F) mesh under going rigid motion.
+  // 
+  // Inputs:
+  //   V  #V by 3 list of mesh positions in reference pose
+  //   F  #F by 3 list of mesh indices into V
+  //   transform  function handle so that transform(t) returns the rigid
+  //     transformation at time t∈[0,1]
+  //   steps  number of time steps: steps=3 --> t∈{0,0.5,1}
+  //   grid_res  number of grid cells on the longest side containing the
+  //     motion (isolevel+1 cells will also be added on each side as padding)
+  //   isolevel  distance level to be contoured as swept volume
+  // Outputs:
+  //   SV  #SV by 3 list of mesh positions of the swept surface
+  //   SF  #SF by 3 list of mesh faces into SV
+  IGL_INLINE void swept_volume(
+    const Eigen::MatrixXd & V,
+    const Eigen::MatrixXi & F,
+    const std::function<Eigen::Affine3d(const double t)> & transform,
+    const size_t steps,
+    const size_t grid_res,
+    const size_t isolevel,
+    Eigen::MatrixXd & SV,
+    Eigen::MatrixXi & SF);
+  
+}
+
+#ifndef IGL_STATIC_LIBRARY
+#  include "swept_volume.cpp"
+#endif
+
+#endif

+ 112 - 0
include/igl/tetrahedralized_grid.cpp

@@ -0,0 +1,112 @@
+#include "tetrahedralized_grid.h"
+#include "grid.h"
+
+template <
+  typename DerivedGV,
+  typename DerivedGT>
+IGL_INLINE void igl::tetrahedralized_grid(
+  const int nx,
+  const int ny,
+  const int nz,
+  const TetrahedralizedGripType type,
+  Eigen::PlainObjectBase<DerivedGV> & GV,
+  Eigen::PlainObjectBase<DerivedGT> & GT)
+{
+  Eigen::RowVector3i res(nx,ny,nz);
+  igl::grid(res,GV);
+  return igl::tetrahedralized_grid(GV,res,GT);
+}
+
+template <
+  typename DerivedGV,
+  typename Derivedside,
+  typename DerivedGT>
+IGL_INLINE void igl::tetrahedralized_grid(
+  const Eigen::MatrixBase<DerivedGV> & GV,
+  const Eigen::MatrixBase<Derivedside> & side,
+  const TetrahedralizedGripType type,
+  Eigen::PlainObjectBase<DerivedGT> & GT)
+{
+  const int nx = side(0);
+  const int ny = side(1);
+  const int nz = side(2);
+  typedef typename DerivedGT::Scalar Index;
+  const int m = (nx-1)*(ny-1)*(nz-1);
+  // Rotationally symmetric
+  int nt = -1;
+  switch(type)
+  {
+    default: assert(false); break;
+    case TETRAHEDRALIZED_GRID_TYPE_5: nt = 5; break;
+    case TETRAHEDRALIZED_GRID_TYPE_6_ROTATIONAL: nt = 6; break;
+  }
+  GT.resize(m*nt,4);
+  {
+    int u = 0;
+    for(int i = 0;i<nx-1;i++)
+    {
+      for(int j = 0;j<ny-1;j++)
+      {
+        for(int k = 0;k<nz-1;k++)
+        {
+          int v1 = (i+0)+nx*((j+0)+ny*(k+0));
+          int v2 = (i+0)+nx*((j+1)+ny*(k+0));
+          int v3 = (i+1)+nx*((j+0)+ny*(k+0));
+          int v4 = (i+1)+nx*((j+1)+ny*(k+0));
+          int v5 = (i+0)+nx*((j+0)+ny*(k+1));
+          int v6 = (i+0)+nx*((j+1)+ny*(k+1));
+          int v7 = (i+1)+nx*((j+0)+ny*(k+1));
+          int v8 = (i+1)+nx*((j+1)+ny*(k+1));
+          switch(type)
+          {
+            case TETRAHEDRALIZED_GRID_TYPE_6_ROTATIONAL:
+              // Rotationally symmetric
+              GT.row(u*nt+0) << v1,v3,v8,v7;
+              GT.row(u*nt+1) << v1,v8,v5,v7;
+              GT.row(u*nt+2) << v1,v3,v4,v8;
+              GT.row(u*nt+3) << v1,v4,v2,v8;
+              GT.row(u*nt+4) << v1,v6,v5,v8;
+              GT.row(u*nt+5) << v1,v2,v6,v8;
+              break;
+            case TETRAHEDRALIZED_GRID_TYPE_5:
+            {
+              // Five
+              bool flip = true;
+              if(((bool(i%2))^ (bool(j%2)))^ (bool(k%2)))
+              {
+                std::swap(v1,v3);
+                std::swap(v2,v4);
+                std::swap(v5,v7);
+                std::swap(v6,v8);
+                flip = false;
+              }
+              GT.row(u*nt+0) << v5,v3,v2,v1;
+              GT.row(u*nt+1) << v3,v2,v8,v5;
+              GT.row(u*nt+2) << v3,v4,v8,v2;
+              GT.row(u*nt+3) << v3,v8,v7,v5;
+              GT.row(u*nt+4) << v2,v6,v8,v5;
+              if(flip)
+              {
+                std::swap(GT(u*nt+0,0),GT(u*nt+0,1));
+                std::swap(GT(u*nt+1,0),GT(u*nt+1,1));
+                std::swap(GT(u*nt+2,0),GT(u*nt+2,1));
+                std::swap(GT(u*nt+3,0),GT(u*nt+3,1));
+                std::swap(GT(u*nt+4,0),GT(u*nt+4,1));
+              }
+              break;
+            }
+          }
+          u++;
+        }
+      }
+    }
+    assert(u == m);
+  }
+}
+
+#ifdef IGL_STATIC_LIBRARY
+// Explicit template instantiation
+// generated by autoexplicit.sh
+template void igl::tetrahedralized_grid<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<int, 1, 3, 1, 1, 3>, Eigen::Matrix<int, -1, -1, 0, -1, -1> >(Eigen::MatrixBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> > const&, Eigen::MatrixBase<Eigen::Matrix<int, 1, 3, 1, 1, 3> > const&, igl::TetrahedralizedGripType, Eigen::PlainObjectBase<Eigen::Matrix<int, -1, -1, 0, -1, -1> >&);
+// generated by autoexplicit.sh
+#endif

+ 67 - 0
include/igl/tetrahedralized_grid.h

@@ -0,0 +1,67 @@
+// This file is part of libigl, a simple c++ geometry processing library.
+// 
+// Copyright (C) 2020 Alec Jacobson <[email protected]>
+// 
+// This Source Code Form is subject to the terms of the Mozilla Public License 
+// v. 2.0. If a copy of the MPL was not distributed with this file, You can 
+// obtain one at http://mozilla.org/MPL/2.0/.
+#ifndef IGL_TETRAHEDRALIZED_GRID_H
+#define IGL_TETRAHEDRALIZED_GRID_H
+#include "igl_inline.h"
+#include <Eigen/Core>
+namespace igl
+{
+  enum TetrahedralizedGripType
+  {
+    TETRAHEDRALIZED_GRID_TYPE_5 = 0,
+    TETRAHEDRALIZED_GRID_TYPE_6_ROTATIONAL = 1,
+    NUM_TETRAHEDRALIZED_GRID_TYPE = 2
+  };
+  // Construct vertices of a regular grid, suitable for input to
+  // `igl::marching_tets`
+  //
+  // Inputs:
+  //   nx  number of grid vertices in x direction
+  //   ny  number of grid vertices in y direction
+  //   nz  number of grid vertices in z direction
+  //   type  type of tetrahedralization of cube to use
+  // Outputs:
+  //   GV  nx*ny*nz by 3 list of grid vertex positions
+  //   GT  (nx-1)*(ny-1)*(nz-1)*k by 4 list of tetrahedron indices into rows of
+  //     V, where k is the number of tets per cube (dependent on type)
+  //
+  //   See also: triangulated_grid, quad_grid
+  template <
+    typename DerivedGV,
+    typename DerivedGT>
+  IGL_INLINE void tetrahedralized_grid(
+    const int nx,
+    const int ny,
+    const int nz,
+    const TetrahedralizedGripType type,
+    Eigen::PlainObjectBase<DerivedGV> & GV,
+    Eigen::PlainObjectBase<DerivedGT> & GT);
+  //
+  // Inputs:
+  //   GV  nx*ny*nz by 3 list of grid vertex positions
+  //   side  3-long list {nx,ny,nz} see above
+  //   type  type of tetrahedralization of cube to use
+  // Outputs:
+  //   GT  (nx-1)*(ny-1)*(nz-1)*k by 4 list of tetrahedron indices into rows of
+  //     V, where k is the number of tets per cube (dependent on type)
+  //
+  template <
+    typename DerivedGV,
+    typename Derivedside,
+    typename DerivedGT>
+  IGL_INLINE void tetrahedralized_grid(
+    const Eigen::MatrixBase<DerivedGV> & GV,
+    const Eigen::MatrixBase<Derivedside> & side,
+    const TetrahedralizedGripType type,
+    Eigen::PlainObjectBase<DerivedGT> & GT);
+}
+#ifndef IGL_STATIC_LIBRARY
+#  include "tetrahedralized_grid.cpp"
+#endif
+#endif 
+

+ 1 - 0
include/igl/unproject.cpp

@@ -72,4 +72,5 @@ template Eigen::Matrix<double, 3, 1, 0, 3, 1> igl::unproject<double>(Eigen::Matr
 template void igl::unproject<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<float, 4, 4, 0, 4, 4>, Eigen::Matrix<float, 4, 4, 0, 4, 4>, Eigen::Matrix<float, 4, 1, 0, 4, 1>, Eigen::Matrix<double, -1, -1, 0, -1, -1> >(Eigen::MatrixBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> > const&, Eigen::MatrixBase<Eigen::Matrix<float, 4, 4, 0, 4, 4> > const&, Eigen::MatrixBase<Eigen::Matrix<float, 4, 4, 0, 4, 4> > const&, Eigen::MatrixBase<Eigen::Matrix<float, 4, 1, 0, 4, 1> > const&, Eigen::PlainObjectBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> >&);
 template void igl::unproject<Eigen::Matrix<float, 3, 1, 0, 3, 1>, Eigen::Matrix<float, 4, 4, 0, 4, 4>, Eigen::Matrix<float, 4, 4, 0, 4, 4>, Eigen::Matrix<float, 4, 1, 0, 4, 1>, Eigen::Matrix<float, 3, 1, 0, 3, 1> >(Eigen::MatrixBase<Eigen::Matrix<float, 3, 1, 0, 3, 1> > const&, Eigen::MatrixBase<Eigen::Matrix<float, 4, 4, 0, 4, 4> > const&, Eigen::MatrixBase<Eigen::Matrix<float, 4, 4, 0, 4, 4> > const&, Eigen::MatrixBase<Eigen::Matrix<float, 4, 1, 0, 4, 1> > const&, Eigen::PlainObjectBase<Eigen::Matrix<float, 3, 1, 0, 3, 1> >&);
 template void igl::unproject<Eigen::Matrix<double, 3, 1, 0, 3, 1>, Eigen::Matrix<float, 4, 4, 0, 4, 4>, Eigen::Matrix<float, 4, 4, 0, 4, 4>, Eigen::Matrix<float, 4, 1, 0, 4, 1>, Eigen::Matrix<double, 3, 1, 0, 3, 1> >(Eigen::MatrixBase<Eigen::Matrix<double, 3, 1, 0, 3, 1> > const&, Eigen::MatrixBase<Eigen::Matrix<float, 4, 4, 0, 4, 4> > const&, Eigen::MatrixBase<Eigen::Matrix<float, 4, 4, 0, 4, 4> > const&, Eigen::MatrixBase<Eigen::Matrix<float, 4, 1, 0, 4, 1> > const&, Eigen::PlainObjectBase<Eigen::Matrix<double, 3, 1, 0, 3, 1> >&);
+template void igl::unproject<Eigen::Matrix<float, 1, 3, 1, 1, 3>, Eigen::Matrix<float, 4, 4, 0, 4, 4>, Eigen::Matrix<float, 4, 4, 0, 4, 4>, Eigen::Matrix<float, 4, 1, 0, 4, 1>, Eigen::Matrix<float, 1, 3, 1, 1, 3> >(Eigen::MatrixBase<Eigen::Matrix<float, 1, 3, 1, 1, 3> > const&, Eigen::MatrixBase<Eigen::Matrix<float, 4, 4, 0, 4, 4> > const&, Eigen::MatrixBase<Eigen::Matrix<float, 4, 4, 0, 4, 4> > const&, Eigen::MatrixBase<Eigen::Matrix<float, 4, 1, 0, 4, 1> > const&, Eigen::PlainObjectBase<Eigen::Matrix<float, 1, 3, 1, 1, 3> >&);
 #endif

+ 25 - 0
include/igl/voxel_grid.cpp

@@ -63,9 +63,34 @@ IGL_INLINE void igl::voxel_grid(
   GV.rowwise() += offset;
 }
 
+template <
+  typename DerivedV,
+  typename DerivedGV,
+  typename Derivedside>
+IGL_INLINE void igl::voxel_grid(
+  const Eigen::MatrixBase<DerivedV> & V, 
+  const typename DerivedV::Scalar offset,
+  const int s,
+  const int pad_count,
+  Eigen::PlainObjectBase<DerivedGV> & GV,
+  Eigen::PlainObjectBase<Derivedside> & side)
+{
+  typedef typename DerivedV::Scalar Scalar;
+  Eigen::AlignedBox<Scalar,3> box;
+  typedef Eigen::Matrix<Scalar,1,3> RowVector3S;
+  assert(V.cols() == 3 && "V must contain positions in 3D");
+  RowVector3S min_ext = V.colwise().minCoeff().array() - offset;
+  RowVector3S max_ext = V.colwise().maxCoeff().array() + offset;
+  box.extend(min_ext.transpose());
+  box.extend(max_ext.transpose());
+  return igl::voxel_grid(box,s,1,GV,side);
+}
+
 #ifdef IGL_STATIC_LIBRARY
 // Explicit template instantiation
 // generated by autoexplicit.sh
+template void igl::voxel_grid<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<int, 1, 3, 1, 1, 3> >(Eigen::MatrixBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> > const&, Eigen::Matrix<double, -1, -1, 0, -1, -1>::Scalar, int, int, Eigen::PlainObjectBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> >&, Eigen::PlainObjectBase<Eigen::Matrix<int, 1, 3, 1, 1, 3> >&);
+// generated by autoexplicit.sh
 template void igl::voxel_grid<float, Eigen::Matrix<float, -1, -1, 0, -1, -1>, Eigen::Matrix<int, 3, 1, 0, 3, 1> >(Eigen::AlignedBox<float, 3> const&, int, int, Eigen::PlainObjectBase<Eigen::Matrix<float, -1, -1, 0, -1, -1> >&, Eigen::PlainObjectBase<Eigen::Matrix<int, 3, 1, 0, 3, 1> >&);
 // generated by autoexplicit.sh
 template void igl::voxel_grid<float, Eigen::Matrix<float, -1, -1, 0, -1, -1>, Eigen::Matrix<int, 1, 3, 1, 1, 3> >(Eigen::AlignedBox<float, 3> const&, int, int, Eigen::PlainObjectBase<Eigen::Matrix<float, -1, -1, 0, -1, -1> >&, Eigen::PlainObjectBase<Eigen::Matrix<int, 1, 3, 1, 1, 3> >&);

+ 11 - 0
include/igl/voxel_grid.h

@@ -32,6 +32,17 @@ namespace igl
     const int pad_count,
     Eigen::PlainObjectBase<DerivedGV> & GV,
     Eigen::PlainObjectBase<Derivedside> & side);
+  template <
+    typename DerivedV,
+    typename DerivedGV,
+    typename Derivedside>
+  IGL_INLINE void voxel_grid(
+    const Eigen::MatrixBase<DerivedV> & V, 
+    const typename DerivedV::Scalar offset,
+    const int s,
+    const int pad_count,
+    Eigen::PlainObjectBase<DerivedGV> & GV,
+    Eigen::PlainObjectBase<Derivedside> & side);
 }
 #ifndef IGL_STATIC_LIBRARY
 #  include "voxel_grid.cpp"

+ 7 - 13
include/igl/writeDMAT.cpp

@@ -84,22 +84,16 @@ IGL_INLINE bool igl::writeDMAT(
 
 #ifdef IGL_STATIC_LIBRARY
 // Explicit template instantiation
-// generated by autoexplicit.sh
-template bool igl::writeDMAT<Eigen::Matrix<int, -1, 3, 0, -1, 3> >(std::basic_string<char, std::char_traits<char>, std::allocator<char> >, Eigen::MatrixBase<Eigen::Matrix<int, -1, 3, 0, -1, 3> > const&, bool);
-// generated by autoexplicit.sh
-template bool igl::writeDMAT<Eigen::Matrix<int, 1, 3, 1, 1, 3> >(std::basic_string<char, std::char_traits<char>, std::allocator<char> >, Eigen::MatrixBase<Eigen::Matrix<int, 1, 3, 1, 1, 3> > const&, bool);
-// generated by autoexplicit.sh
-template bool igl::writeDMAT<Eigen::Matrix<int, 3, 1, 0, 3, 1> >(std::basic_string<char, std::char_traits<char>, std::allocator<char> >, Eigen::MatrixBase<Eigen::Matrix<int, 3, 1, 0, 3, 1> > const&, bool);
-// generated by autoexplicit.sh
-template bool igl::writeDMAT<Eigen::Matrix<float, -1, -1, 1, -1, -1> >(std::basic_string<char, std::char_traits<char>, std::allocator<char> >, Eigen::MatrixBase<Eigen::Matrix<float, -1, -1, 1, -1, -1> > const&, bool);
-// generated by autoexplicit.sh
-template bool igl::writeDMAT<Eigen::Matrix<float, -1, -1, 0, -1, -1> >(std::basic_string<char, std::char_traits<char>, std::allocator<char> >, Eigen::MatrixBase<Eigen::Matrix<float, -1, -1, 0, -1, -1> > const&, bool);
-// generated by autoexplicit.sh
-template bool igl::writeDMAT<Eigen::Matrix<float, -1, 1, 0, -1, 1> >(std::basic_string<char, std::char_traits<char>, std::allocator<char> >, Eigen::MatrixBase<Eigen::Matrix<float, -1, 1, 0, -1, 1> > const&, bool);
 template bool igl::writeDMAT<Eigen::Matrix<double, -1, -1, 0, -1, -1> >(std::basic_string<char, std::char_traits<char>, std::allocator<char> >, Eigen::MatrixBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> > const&, bool);
+template bool igl::writeDMAT<Eigen::Matrix<double, -1, 1, 0, -1, 1> >(std::basic_string<char, std::char_traits<char>, std::allocator<char> >, Eigen::MatrixBase<Eigen::Matrix<double, -1, 1, 0, -1, 1> > const&, bool);
 template bool igl::writeDMAT<Eigen::Matrix<double, 1, 3, 1, 1, 3> >(std::string, Eigen::MatrixBase<Eigen::Matrix<double, 1, 3, 1, 1, 3> > const&, bool);
+template bool igl::writeDMAT<Eigen::Matrix<float, -1, -1, 0, -1, -1> >(std::basic_string<char, std::char_traits<char>, std::allocator<char> >, Eigen::MatrixBase<Eigen::Matrix<float, -1, -1, 0, -1, -1> > const&, bool);
+template bool igl::writeDMAT<Eigen::Matrix<float, -1, -1, 1, -1, -1> >(std::basic_string<char, std::char_traits<char>, std::allocator<char> >, Eigen::MatrixBase<Eigen::Matrix<float, -1, -1, 1, -1, -1> > const&, bool);
+template bool igl::writeDMAT<Eigen::Matrix<float, -1, 1, 0, -1, 1> >(std::basic_string<char, std::char_traits<char>, std::allocator<char> >, Eigen::MatrixBase<Eigen::Matrix<float, -1, 1, 0, -1, 1> > const&, bool);
 template bool igl::writeDMAT<Eigen::Matrix<float, 1, 3, 1, 1, 3> >(std::string, Eigen::MatrixBase<Eigen::Matrix<float, 1, 3, 1, 1, 3> > const&, bool);
 template bool igl::writeDMAT<Eigen::Matrix<int, -1, -1, 0, -1, -1> >(std::basic_string<char, std::char_traits<char>, std::allocator<char> >, Eigen::MatrixBase<Eigen::Matrix<int, -1, -1, 0, -1, -1> > const&, bool);
 template bool igl::writeDMAT<Eigen::Matrix<int, -1, 2, 0, -1, 2> >(std::basic_string<char, std::char_traits<char>, std::allocator<char> >, Eigen::MatrixBase<Eigen::Matrix<int, -1, 2, 0, -1, 2> > const&, bool);
-template bool igl::writeDMAT<Eigen::Matrix<double, -1, 1, 0, -1, 1> >(std::basic_string<char, std::char_traits<char>, std::allocator<char> >, Eigen::MatrixBase<Eigen::Matrix<double, -1, 1, 0, -1, 1> > const&, bool);
+template bool igl::writeDMAT<Eigen::Matrix<int, -1, 3, 0, -1, 3> >(std::basic_string<char, std::char_traits<char>, std::allocator<char> >, Eigen::MatrixBase<Eigen::Matrix<int, -1, 3, 0, -1, 3> > const&, bool);
+template bool igl::writeDMAT<Eigen::Matrix<int, 1, 3, 1, 1, 3> >(std::basic_string<char, std::char_traits<char>, std::allocator<char> >, Eigen::MatrixBase<Eigen::Matrix<int, 1, 3, 1, 1, 3> > const&, bool);
+template bool igl::writeDMAT<Eigen::Matrix<int, 3, 1, 0, 3, 1> >(std::basic_string<char, std::char_traits<char>, std::allocator<char> >, Eigen::MatrixBase<Eigen::Matrix<int, 3, 1, 0, 3, 1> > const&, bool);
 #endif

+ 1 - 1
include/igl/writePLY.cpp

@@ -147,7 +147,7 @@ bool writePLY(
         _ed.resize(ED.size());
         Eigen::Map<Eigen::Matrix<EDScalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > >( &_ed[0], ED.rows(), ED.cols() ) = ED;
 
-        file.add_properties_to_element("face", FDheader,
+        file.add_properties_to_element("edge", EDheader,
             tynyply_type<EDScalar>(), ED.rows(), reinterpret_cast<uint8_t*>( &_ed[0] ), tinyply::Type::INVALID, 0);
     }
 

+ 17 - 5
tests/include/igl/writePLY.cpp

@@ -27,9 +27,16 @@ TEST_CASE("writePLY: bunny.ply", "[igl]")
     Eigen::MatrixXd VD2(V1.rows(),VD1.cols()+1);
     VD2<<VD1,dummy_data;
 
+    Fheader1.push_back("face_data");
+    Eigen::VectorXd face_data(F1.rows());
+    for(size_t i=0;i<F1.rows();++i)
+        face_data(i)=(double)i;
+    Eigen::MatrixXd FD2(F1.rows(),FD1.cols()+1);
+    // there is no face data in the input file
+    FD2<<face_data;
 
     // test that saving preserves all the data, including new data column
-    REQUIRE (igl::writePLY("test_bunny.ply", V1, F1, E1, N1, UV1, VD2, Vheader1, FD1,Fheader1, ED1, Eheader1, comments1, igl::FileEncoding::Binary));
+    REQUIRE (igl::writePLY("test_bunny.ply", V1, F1, E1, N1, UV1, VD2, Vheader1, FD2,Fheader1, ED1, Eheader1, comments1, igl::FileEncoding::Binary));
 
     Eigen::MatrixXd V,N,UV,VD,FD,ED;
     Eigen::MatrixXi F,E;
@@ -65,10 +72,15 @@ TEST_CASE("writePLY: bunny.ply", "[igl]")
     REQUIRE (Vheader[1] == "intensity" );
     REQUIRE (Vheader[2] == "dummy_data" );
 
-    // no Face data or edge data
-    REQUIRE (FD.rows() == 0);
-    REQUIRE (FD.cols() == 0);
-    REQUIRE (Fheader.size() == 0);
+    // Face should have only one column
+    REQUIRE (Fheader.size() == 1);
+    REQUIRE (Fheader[0] == "face_data" );
+    REQUIRE (FD.rows() == F.rows());
+    REQUIRE (FD.cols() == 1);
+
+    // the dummy column contents check
+    for(size_t i=0;i<F.rows();++i)
+        REQUIRE (FD(i,0) == (double)i);
 
     REQUIRE (ED.rows() == 0);
     REQUIRE (ED.cols() == 0);

+ 5 - 0
tutorial/608_RayTrace/CMakeLists.txt

@@ -0,0 +1,5 @@
+get_filename_component(PROJECT_NAME ${CMAKE_CURRENT_SOURCE_DIR} NAME)
+project(${PROJECT_NAME})
+
+add_executable(${PROJECT_NAME} main.cpp)
+target_link_libraries(${PROJECT_NAME} igl::core igl::embree igl::png tutorials)

+ 70 - 0
tutorial/608_RayTrace/main.cpp

@@ -0,0 +1,70 @@
+#include <igl/gaussian_curvature.h>
+#include <igl/massmatrix.h>
+#include <igl/invert_diag.h>
+#include <igl/read_triangle_mesh.h>
+#include <igl/png/writePNG.h>
+#include <igl/PI.h>
+#include <Eigen/Geometry>
+// embree
+#include <igl/embree/EmbreeRenderer.h>
+
+#include "tutorial_shared_path.h"
+
+#include <iostream>
+
+int main(int argc, char *argv[])
+{
+  int width=640;
+  int height=480;
+
+  Eigen::MatrixXd V;
+  Eigen::MatrixXi F;
+
+  const char *mesh_file=argc > 1 ? argv[1] : TUTORIAL_SHARED_PATH "/fertility.off";
+  const char *png_file=argc > 2 ? argv[2]: "fertility_curvature.png";
+
+  // Load mesh 
+  igl::read_triangle_mesh(mesh_file, V,F);
+  
+  Eigen::VectorXd K;
+  // Compute integral of Gaussian curvature
+  igl::gaussian_curvature(V,F,K);
+  // Compute mass matrix
+  Eigen::SparseMatrix<double> M,Minv;
+  igl::massmatrix(V,F,igl::MASSMATRIX_TYPE_DEFAULT,M);
+  igl::invert_diag(M,Minv);
+  // Divide by area to get integral average
+  K = (Minv*K).eval();
+
+  // embree object
+  igl::embree::EmbreeRenderer er;
+  er.set_mesh(V,F,true);
+
+  //er.set_uniform_color(Eigen::RowVector3d(0.3,0.3,0.3));
+  er.set_data(K,igl::COLOR_MAP_TYPE_JET);
+
+  Eigen::Matrix3d rot_matrix;
+
+  // specify rotation
+  rot_matrix =  Eigen::AngleAxisd( 10*igl::PI/180.0, Eigen::Vector3d::UnitX())
+              * Eigen::AngleAxisd(  5*igl::PI/180.0, Eigen::Vector3d::UnitY())
+              * Eigen::AngleAxisd(  4*igl::PI/180.0, Eigen::Vector3d::UnitZ());
+  er.set_rot(rot_matrix);
+
+  er.set_zoom(1.5);
+  er.set_orthographic(false);
+     
+  Eigen::Matrix<unsigned char,Eigen::Dynamic,Eigen::Dynamic> R(width, height);
+  Eigen::Matrix<unsigned char,Eigen::Dynamic,Eigen::Dynamic> G(width, height);
+  Eigen::Matrix<unsigned char,Eigen::Dynamic,Eigen::Dynamic> B(width, height);
+  Eigen::Matrix<unsigned char,Eigen::Dynamic,Eigen::Dynamic> A(width, height);
+
+  // render view using embree
+  er.render_buffer(R,G,B,A);
+
+  std::cout<<"Rendered scene saved to "<<png_file<<std::endl;
+
+  // save to PNG file
+  igl::png::writePNG(R,G,B,A,png_file);
+  return 0;
+}

+ 3 - 3
tutorial/705_MarchingCubes/main.cpp

@@ -1,4 +1,4 @@
-#include <igl/copyleft/marching_cubes.h>
+#include <igl/marching_cubes.h>
 #include <igl/signed_distance.h>
 #include <igl/read_triangle_mesh.h>
 #include <igl/opengl/glfw/Viewer.h>
@@ -55,8 +55,8 @@ int main(int argc, char * argv[])
   cout<<"Marching cubes..."<<endl;
   MatrixXd SV,BV;
   MatrixXi SF,BF;
-  igl::copyleft::marching_cubes(S,GV,res(0),res(1),res(2),SV,SF);
-  igl::copyleft::marching_cubes(B,GV,res(0),res(1),res(2),BV,BF);
+  igl::marching_cubes(S,GV,res(0),res(1),res(2),0,SV,SF);
+  igl::marching_cubes(B,GV,res(0),res(1),res(2),0,BV,BF);
 
   cout<<R"(Usage:
 '1'  Show original mesh.

+ 2 - 3
tutorial/707_SweptVolume/main.cpp

@@ -1,8 +1,7 @@
 #include <igl/read_triangle_mesh.h>
 #include <igl/get_seconds.h>
 #include <igl/material_colors.h>
-#include <igl/copyleft/marching_cubes.h>
-#include <igl/copyleft/swept_volume.h>
+#include <igl/swept_volume.h>
 #include <igl/opengl/glfw/Viewer.h>
 #include <igl/PI.h>
 #include <Eigen/Core>
@@ -39,7 +38,7 @@ int main(int argc, char * argv[])
   const int time_steps = 200;
   const double isolevel = 0.1;
   std::cerr<<"Computing swept volume...";
-  igl::copyleft::swept_volume(
+  igl::swept_volume(
     V,F,transform,time_steps,grid_size,isolevel,SV,SF);
   std::cerr<<" finished."<<std::endl;
 

+ 1 - 1
tutorial/714_MarchingTets/CMakeLists.txt

@@ -2,4 +2,4 @@ get_filename_component(PROJECT_NAME ${CMAKE_CURRENT_SOURCE_DIR} NAME)
 project(${PROJECT_NAME})
 
 add_executable(${PROJECT_NAME} main.cpp)
-target_link_libraries(${PROJECT_NAME} igl::core igl::opengl igl::opengl_glfw igl::tetgen tutorials)
+target_link_libraries(${PROJECT_NAME} igl::core igl::opengl igl::opengl_glfw tutorials)

+ 81 - 28
tutorial/714_MarchingTets/main.cpp

@@ -1,48 +1,101 @@
 #include <igl/opengl/glfw/Viewer.h>
-#include <igl/copyleft/tetgen/tetrahedralize.h>
 #include <igl/readOBJ.h>
+#include <igl/read_triangle_mesh.h>
+#include <igl/voxel_grid.h>
+#include <igl/tetrahedralized_grid.h>
 #include <igl/marching_tets.h>
+#include <igl/signed_distance.h>
+#include <igl/writeOBJ.h>
+#include <igl/get_seconds.h>
 #include <Eigen/Core>
 
 #include "tutorial_shared_path.h"
 
+#include <igl/marching_cubes.h>
 
 int main(int argc, char * argv[])
 {
+  const auto & tictoc = []()
+  {
+    static double t_start = igl::get_seconds();
+    double diff = igl::get_seconds()-t_start;
+    t_start += diff;
+    return diff;
+  };
 
   // Load a surface mesh which is a cube
-  Eigen::MatrixXd surfaceV;
-  Eigen::MatrixXi surfaceF;
-  igl::readOBJ(TUTORIAL_SHARED_PATH "/cube.obj", surfaceV, surfaceF);
+  Eigen::MatrixXd V;
+  Eigen::MatrixXi F;
+  igl::read_triangle_mesh(
+    argc>1?argv[1]: TUTORIAL_SHARED_PATH "/armadillo.obj",V,F);
 
-  // Find the centroid of the loaded mesh
-  Eigen::RowVector3d surfaceCenter = surfaceV.colwise().sum() / surfaceV.rows();
+  Eigen::RowVector3i side;
+  Eigen::MatrixXd TV;
+  tictoc();
+  igl::voxel_grid(V,0,100,1,TV,side);
+  printf("igl::voxel_grid               %g secs\n",tictoc());
+  Eigen::MatrixXi TT5,TT6;
+  tictoc();
+  igl::tetrahedralized_grid(TV,side,igl::TETRAHEDRALIZED_GRID_TYPE_5,TT5);
+  printf("igl::tetrahedralized_grid     %g secs\n",tictoc());
+  igl::tetrahedralized_grid(TV,side,igl::TETRAHEDRALIZED_GRID_TYPE_6_ROTATIONAL,TT6);
+  printf("igl::tetrahedralized_grid     %g secs\n",tictoc());
 
-  // Center the mesh about the origin
-  surfaceV.rowwise() -= surfaceCenter;
+  tictoc();
+  Eigen::VectorXd S;
+  {
+    Eigen::VectorXi I;
+    Eigen::MatrixXd C,N;
+    igl::signed_distance(
+      TV,V,F,
+      igl::SIGNED_DISTANCE_TYPE_FAST_WINDING_NUMBER,
+      std::numeric_limits<double>::min(),
+      std::numeric_limits<double>::max(),
+      S,I,C,N);
+  }
+  printf("igl::signed_distance          %g secs\n",tictoc());
+  
+  std::vector<Eigen::MatrixXd> SV(3);
+  std::vector<Eigen::MatrixXi> SF(3);
+  igl::marching_tets(TV,TT5,S,0,SV[0],SF[0]);
+  printf("igl::marching_tets5           %g secs\n",tictoc());
+  igl::marching_tets(TV,TT6,S,0,SV[1],SF[1]);
+  printf("igl::marching_tets6           %g secs\n",tictoc());
+  tictoc();
+  igl::marching_cubes(S,TV,side(0),side(1),side(2),0,SV[2],SF[2]);
+  printf("igl::marching_cubes           %g secs\n",tictoc());
 
-  // Tetrahedralize the surface mesh
-  Eigen::MatrixXd TV; // Tet mesh vertices
-  Eigen::MatrixXi TF; // Tet mesh boundary face indices
-  Eigen::MatrixXi TT; // Tet mesh tetrahedron indices
-  igl::copyleft::tetgen::tetrahedralize(surfaceV, surfaceF, "pq1.414a0.0001", TV, TT, TF);
 
-  // Compute a scalar at each tet vertex which is the distance from the vertex to the origin
-  Eigen::VectorXd S = TV.rowwise().norm();
-
-  // Compute a mesh (stored in SV, SF) representing the iso-level-set for the isovalue 0.5
-  Eigen::MatrixXd SV;
-  Eigen::MatrixXi SF;
-  igl::marching_tets(TV, TT, S, 0.45, SV, SF);
+  //igl::writeOBJ("tmc.obj",SV,SF);
 
   // Draw the mesh stored in (SV, SF)
-  igl::opengl::glfw::Viewer viewer;
-  viewer.data().set_mesh(SV, SF);
-  viewer.callback_key_down =
-    [&](igl::opengl::glfw::Viewer & viewer, unsigned char key, int mod)->bool
+  igl::opengl::glfw::Viewer vr;
+  vr.data().set_mesh(V,F);
+  vr.data().is_visible = false;
+  vr.append_mesh();
+  int sel = 0;
+  const auto update = [&]()
+  {
+    vr.data().clear();
+    vr.data().set_mesh(SV[sel],SF[sel]);
+  };
+  vr.callback_key_pressed = [&](decltype(vr) &,unsigned int key, int mod)
+  {
+    switch(key)
     {
-      viewer.data().set_face_based(true);
-      return true;
-    };
-  viewer.launch();
+      case ',': 
+      case '.': 
+        sel = (sel+SV.size()+(key=='.'?1:-1))%SV.size();
+        update();
+        return true;
+      case ' ': 
+        vr.data_list[0].is_visible = !vr.data_list[0].is_visible;
+        vr.data_list[1].is_visible = !vr.data_list[1].is_visible;
+        vr.selected_data_index = (vr.selected_data_index+1)%2;
+        return true;
+    }
+    return false;
+  };
+  update();
+  vr.launch();
 }

+ 3 - 0
tutorial/CMakeLists.txt

@@ -134,6 +134,9 @@ if(TUTORIALS_CHAPTER6)
     add_subdirectory("111_MatCap")
     add_subdirectory("607_ScreenCapture")
   endif()
+  if(LIBIGL_WITH_PNG AND LIBIGL_WITH_EMBREE)
+    add_subdirectory("608_RayTrace")
+  endif()
   if(LIBIGL_WITH_CGAL)
     add_subdirectory("609_Boolean")
     add_subdirectory("610_CSGTree")