Browse Source

Merge branch 'master' of github.com:libigl/libigl into alecjacobson

Former-commit-id: 6174a89c7a08584b29e83505625829a13d366dbf
Alec Jacobson 8 years ago
parent
commit
8beb89fea9
35 changed files with 1070 additions and 29 deletions
  1. 4 0
      README.md
  2. 4 0
      index.html
  3. 5 0
      python/CMakeLists.txt
  4. 18 0
      python/modules/py_igl_bbw.cpp
  5. 2 0
      python/modules/py_igl_embree.cpp
  6. 13 7
      python/modules/py_igl_viewer.cpp
  7. 13 0
      python/modules/py_typedefs.cpp
  8. 5 0
      python/modules/py_typedefs.h
  9. 52 9
      python/modules/py_vector.cpp
  10. 190 0
      python/py_doc.cpp
  11. 15 0
      python/py_doc.h
  12. 27 0
      python/py_igl.cpp
  13. 42 0
      python/py_igl/bbw/py_bbw.cpp
  14. 13 0
      python/py_igl/embree/py_line_mesh_intersection.cpp
  15. 12 0
      python/py_igl/py_barycentric_to_global.cpp
  16. 24 0
      python/py_igl/py_boundary_conditions.cpp
  17. 10 0
      python/py_igl/py_column_to_quats.cpp
  18. 36 0
      python/py_igl/py_deform_skeleton.cpp
  19. 12 0
      python/py_igl/py_directed_edge_orientations.cpp
  20. 14 0
      python/py_igl/py_directed_edge_parents.cpp
  21. 21 0
      python/py_igl/py_dqs.cpp
  22. 62 0
      python/py_igl/py_forward_kinematics.cpp
  23. 67 0
      python/py_igl/py_lbs_matrix.cpp
  24. 12 0
      python/py_igl/py_normalize_row_lengths.cpp
  25. 12 0
      python/py_igl/py_normalize_row_sums.cpp
  26. 54 0
      python/py_igl/py_readTGF.cpp
  27. 25 4
      python/python_shared.cpp
  28. 3 0
      python/scripts/py_igl.mako
  29. 12 4
      python/scripts/python_shared.mako
  30. 2 2
      python/tutorial/402_PolyharmonicDeformation.py
  31. 145 0
      python/tutorial/403_BoundedBiharmonicWeights.py
  32. 140 0
      python/tutorial/404_DualQuaternionSkinning.py
  33. 2 1
      shared/cmake/CMakeLists.txt
  34. 1 1
      tutorial/tutorial.html.REMOVED.git-id
  35. 1 1
      tutorial/tutorial.md.REMOVED.git-id

+ 4 - 0
README.md

@@ -43,6 +43,10 @@ and Windows with Visual Studio 2015 Community Edition.
 As of version 1.0, libigl includes an introductory
 [tutorial](http://libigl.github.io/libigl/tutorial/tutorial.html) that covers many functionalities.
 
+## libigl example project
+
+We provide a [blank project example](https://github.com/libigl/libigl-example-project) showing how to use libigl and cmake. Feel free and encouraged to copy or fork this project as a way of starting a new personal project using libigl.
+
 ## Installation
 
 Libigl is a **header-only** library. You do **not** need to build anything to

+ 4 - 0
index.html

@@ -59,6 +59,10 @@ and Windows with Visual Studio 2015 Community Edition.</p>
 <p>As of version 1.0, libigl includes an introductory
 <a href="http://libigl.github.io/libigl/tutorial/tutorial.html">tutorial</a> that covers many functionalities.</p>
 
+<h2 id="libiglexampleproject">libigl example project</h2>
+
+<p>We provide a <a href="https://github.com/libigl/libigl-example-project">blank project example</a> showing how to use libigl and cmake. Feel free and encouraged to copy or fork this project as a way of starting a new personal project using libigl.</p>
+
 <h2 id="installation">Installation</h2>
 
 <p>Libigl is a <strong>header-only</strong> library. You do <strong>not</strong> need to build anything to

+ 5 - 0
python/CMakeLists.txt

@@ -120,6 +120,11 @@ if (LIBIGL_WITH_COPYLEFT)
   list(APPEND SHARED_SOURCES "modules/copyleft/py_igl_copyleft.cpp")
 endif ()
 
+if (LIBIGL_WITH_BBW)
+  add_definitions(-DPY_BBW)
+  list(APPEND SHARED_SOURCES "modules/py_igl_bbw.cpp")
+endif ()
+
 if (LIBIGL_WITH_PNG)
   add_definitions(-DPY_PNG)
   list(APPEND SHARED_SOURCES "modules/py_igl_png.cpp")

+ 18 - 0
python/modules/py_igl_bbw.cpp

@@ -0,0 +1,18 @@
+//#include <Eigen/Geometry>
+//#include <Eigen/Dense>
+//#include <Eigen/Sparse>
+
+
+#include "../python_shared.h"
+
+#include <igl/bbw/bbw.h>
+
+
+void python_export_igl_bbw(py::module &me) {
+
+  py::module m = me.def_submodule(
+    "bbw", "Wrappers for libigl functions that use bbw");
+
+  #include "../py_igl/bbw/py_bbw.cpp"
+
+}

+ 2 - 0
python/modules/py_igl_embree.cpp

@@ -7,6 +7,7 @@
 
 #include <igl/embree/ambient_occlusion.h>
 #include <igl/embree/reorient_facets_raycast.h>
+#include <igl/embree/line_mesh_intersection.h>
 
 
 void python_export_igl_embree(py::module &me) {
@@ -16,5 +17,6 @@ void python_export_igl_embree(py::module &me) {
 
   #include "../py_igl/embree/py_ambient_occlusion.cpp"
   #include "../py_igl/embree/py_reorient_facets_raycast.cpp"
+  #include "../py_igl/embree/py_line_mesh_intersection.cpp"
 
 }

+ 13 - 7
python/modules/py_igl_viewer.cpp

@@ -188,9 +188,15 @@ py::class_<igl::viewer::ViewerCore> viewercore_class(me, "ViewerCore");
     })
 
     .def_readwrite("lighting_factor",&igl::viewer::ViewerCore::lighting_factor)
-
     .def_readwrite("model_zoom",&igl::viewer::ViewerCore::model_zoom)
 
+    .def_property("trackball_angle",
+    [](const igl::viewer::ViewerCore& core) {return Eigen::Quaterniond(core.trackball_angle.cast<double>());},
+    [](igl::viewer::ViewerCore& core, const Eigen::Quaterniond& q)
+    {
+      core.trackball_angle = Eigen::Quaternionf(q.cast<float>());
+    })
+
     .def_property("model_translation",
     [](const igl::viewer::ViewerCore& core) {return Eigen::MatrixXd(core.model_translation.cast<double>());},
     [](igl::viewer::ViewerCore& core, const Eigen::MatrixXd& v)
@@ -316,13 +322,13 @@ py::class_<igl::viewer::ViewerCore> viewercore_class(me, "ViewerCore");
 // UI Enumerations
     py::class_<igl::viewer::Viewer> viewer_class(me, "Viewer");
 
-    #ifdef IGL_VIEWER_WITH_NANOGUI
-    py::object fh = (py::object) py::module::import("nanogui").attr("FormHelper");
-    py::class_<nanogui::FormHelper> form_helper_class(me, "FormHelper", fh);
+//    #ifdef IGL_VIEWER_WITH_NANOGUI
+//    py::object fh = (py::object) py::module::import("nanogui").attr("FormHelper");
+//    py::class_<nanogui::FormHelper> form_helper_class(me, "FormHelper", fh);
 
-    py::object screen = (py::object) py::module::import("nanogui").attr("Screen");
-    py::class_<nanogui::Screen> screen_class(me, "Screen", screen);
-    #endif
+//    py::object screen = (py::object) py::module::import("nanogui").attr("Screen");
+//    py::class_<nanogui::Screen> screen_class(me, "Screen", screen);
+//    #endif
 
     py::enum_<igl::viewer::Viewer::MouseButton>(viewer_class, "MouseButton")
         .value("Left", igl::viewer::Viewer::MouseButton::Left)

+ 13 - 0
python/modules/py_typedefs.cpp

@@ -0,0 +1,13 @@
+py::class_<RotationList>(m, "RotationList")
+    .def(py::init<>())
+    .def(py::init<size_t>())
+    .def("pop_back", &RotationList::pop_back)
+    /* There are multiple versions of push_back(), etc. Select the right ones. */
+    .def("append", (void (RotationList::*)(const Eigen::Quaterniond &)) &RotationList::push_back)
+    .def("back", (Eigen::Quaterniond &(RotationList::*)()) &RotationList::back)
+    .def("__len__", [](const RotationList &v) { return v.size(); })
+    .def("__getitem__", [](const RotationList &v, int b) { return v.at(b); })
+    .def("__setitem__", [](RotationList &v, int b, Eigen::Quaterniond &c) { return v.at(b) = c; })
+    .def("__iter__", [](RotationList &v) {
+       return py::make_iterator(v.begin(), v.end());
+}, py::keep_alive<0, 1>());

+ 5 - 0
python/modules/py_typedefs.h

@@ -0,0 +1,5 @@
+typedef std::vector<Eigen::Quaterniond,Eigen::aligned_allocator<Eigen::Quaterniond> > RotationList;
+PYBIND11_MAKE_OPAQUE(RotationList);
+
+//typedef std::vector<Eigen::Vector3d> TranslationList;
+//PYBIND11_MAKE_OPAQUE(TranslationList);

+ 52 - 9
python/modules/py_vector.cpp

@@ -68,7 +68,7 @@ py::class_<Type> bind_eigen_2(py::module &m, const char *name,
         })
         .def("__init__", [](Type &m, py::buffer b) {
             py::buffer_info info = b.request();
-            if (info.format != py::format_descriptor<Scalar>::value())
+            if (info.format != py::format_descriptor<Scalar>::value)
                 throw std::runtime_error("Incompatible buffer format!");
             if (info.ndim == 1) {
                 new (&m) Type(info.shape[0], 1);
@@ -319,7 +319,7 @@ py::class_<Type> bind_eigen_2(py::module &m, const char *name,
                 m.data(),                /* Pointer to buffer */
                 sizeof(Scalar),          /* Size of one scalar */
                 /* Python struct-style format descriptor */
-                py::format_descriptor<Scalar>::value(),
+                py::format_descriptor<Scalar>::value,
                 2,                       /* Number of dimensions */
                 { (size_t) m.rows(),     /* Buffer dimensions */
                   (size_t) m.cols() },
@@ -692,10 +692,12 @@ void python_export_vector(py::module &m) {
     .def("solve",[](const Eigen::SimplicialLLT<Eigen::SparseMatrix<double > >& s, const Eigen::MatrixXd& rhs) { return Eigen::MatrixXd(s.solve(rhs)); })
     ;
 
+    // Bindings for Affine3d
     py::class_<Eigen::Affine3d > affine3d(me, "Affine3d");
 
     affine3d
     .def(py::init<>())
+    .def_static("Identity", []() { return Eigen::Affine3d::Identity(); })
     .def("setIdentity",[](Eigen::Affine3d& a){
         return a.setIdentity();
     })
@@ -703,6 +705,9 @@ void python_export_vector(py::module &m) {
         assert_is_Vector3("axis", axis);
         return a.rotate(Eigen::AngleAxisd(angle, Eigen::Vector3d(axis)));
     })
+    .def("rotate",[](Eigen::Affine3d& a, Eigen::Quaterniond quat) {
+        return a.rotate(quat);
+    })
     .def("translate",[](Eigen::Affine3d& a, Eigen::MatrixXd offset) {
         assert_is_Vector3("offset", offset);
         return a.translate(Eigen::Vector3d(offset));
@@ -711,13 +716,51 @@ void python_export_vector(py::module &m) {
         return Eigen::MatrixXd(a.matrix());
     })
     ;
-    /* Bindings for Quaterniond*/
-    //py::class_<Eigen::Quaterniond > quaterniond(me, "Quaterniond");
-    //
-    // quaterniond
-    // .def(py::init<>())
-    // .def(py::init<double, double, double, double>())
-    // ;
+    // Bindings for Quaterniond
+    py::class_<Eigen::Quaterniond > quaterniond(me, "Quaterniond");
+    
+    quaterniond
+    .def(py::init<>())
+    .def(py::init<double, double, double, double>())
+    .def("__init__", [](Eigen::Quaterniond &q, double angle, Eigen::MatrixXd axis) {
+        assert_is_Vector3("axis", axis);
+        new (&q) Eigen::Quaterniond(Eigen::AngleAxisd(angle, Eigen::Vector3d(axis)));
+    })
+    .def_static("Identity", []() { return Eigen::Quaterniond::Identity(); })
+    .def("__repr__", [](const Eigen::Quaterniond &v) {
+        std::ostringstream oss;
+        oss << "(" << v.w() << ", " << v.x() << ", " << v.y() << ", " << v.z() << ")";
+        return oss.str();
+    })
+    .def("conjugate",[](Eigen::Quaterniond& q) {
+        return q.conjugate();
+    })
+    .def("normalize",[](Eigen::Quaterniond& q) {
+        return q.normalize();
+    })
+    .def("slerp",[](Eigen::Quaterniond& q, double & t, Eigen::Quaterniond other) {
+        return q.slerp(t, other);
+    })
+//    .def_cast(-py::self)
+//    .def_cast(py::self + py::self)
+//    .def_cast(py::self - py::self)
+    .def_cast(py::self * py::self)
+    // .def_cast(py::self - Scalar())
+    // .def_cast(py::self * Scalar())
+    // .def_cast(py::self / Scalar())
+
+//    .def("__mul__", []
+//    (const Type &a, const Scalar& b)
+//    {
+//      return Eigen::Matrix<Scalar,Eigen::Dynamic,Eigen::Dynamic>(a * b);
+//    })
+//    .def("__rmul__", [](const Type& a, const Scalar& b)
+//    {
+//      return Eigen::Matrix<Scalar,Eigen::Dynamic,Eigen::Dynamic>(b * a);
+//    })
+    ;
+
+    
 
 
 

+ 190 - 0
python/py_doc.cpp

@@ -76,6 +76,59 @@ const char *__doc_igl_barycentric_coordinates = R"igl_Qu8mg5v7(// Compute baryce
   // Outputs:
   //   L  #P by 4 list of barycentric coordinates
   //   )igl_Qu8mg5v7";
+const char *__doc_igl_barycentric_to_global = R"igl_Qu8mg5v7(// Converts barycentric coordinates in the embree form to 3D coordinates
+  // Embree stores barycentric coordinates as triples: fid, bc1, bc2
+  // fid is the id of a face, bc1 is the displacement of the point wrt the 
+  // first vertex v0 and the edge v1-v0. Similarly, bc2 is the displacement
+  // wrt v2-v0.
+  // 
+  // Input:
+  // V:  #Vx3 Vertices of the mesh
+  // F:  #Fxe Faces of the mesh
+  // bc: #Xx3 Barycentric coordinates, one row per point
+  //
+  // Output:
+  // #X: #Xx3 3D coordinates of all points in bc
+  //   )igl_Qu8mg5v7";
+const char *__doc_igl_bbw_bbw = R"igl_Qu8mg5v7(// Compute Bounded Biharmonic Weights on a given domain (V,Ele) with a given
+    // set of boundary conditions
+    //
+    // Templates
+    //   DerivedV  derived type of eigen matrix for V (e.g. MatrixXd)
+    //   DerivedF  derived type of eigen matrix for F (e.g. MatrixXi)
+    //   Derivedb  derived type of eigen matrix for b (e.g. VectorXi)
+    //   Derivedbc  derived type of eigen matrix for bc (e.g. MatrixXd)
+    //   DerivedW  derived type of eigen matrix for W (e.g. MatrixXd)
+    // Inputs:
+    //   V  #V by dim vertex positions
+    //   Ele  #Elements by simplex-size list of element indices
+    //   b  #b boundary indices into V
+    //   bc #b by #W list of boundary values
+    //   data  object containing options, intial guess --> solution and results
+    // Outputs:
+    //   W  #V by #W list of *unnormalized* weights to normalize use
+    //    igl::normalize_row_sums(W,W);
+    // Returns true on success, false on failure)igl_Qu8mg5v7";
+const char *__doc_igl_boundary_conditions = R"igl_Qu8mg5v7(// Compute boundary conditions for automatic weights computation. This
+  // function expects that the given mesh (V,Ele) has sufficient samples
+  // (vertices) exactly at point handle locations and exactly along bone and
+  // cage edges.
+  //
+  // Inputs:
+  //   V  #V by dim list of domain vertices
+  //   Ele  #Ele by simplex-size list of simplex indices
+  //   C  #C by dim list of handle positions
+  //   P  #P by 1 list of point handle indices into C
+  //   BE  #BE by 2 list of bone edge indices into C
+  //   CE  #CE by 2 list of cage edge indices into *P*
+  // Outputs:
+  //   b  #b list of boundary indices (indices into V of vertices which have
+  //     known, fixed values)
+  //   bc #b by #weights list of known/fixed values for boundary vertices
+  //     (notice the #b != #weights in general because #b will include all the
+  //     intermediary samples along each bone, etc.. The ordering of the
+  //     weights corresponds to [P;BE]
+  // Returns true if boundary conditions make sense)igl_Qu8mg5v7";
 const char *__doc_igl_boundary_facets = R"igl_Qu8mg5v7(// BOUNDARY_FACETS Determine boundary faces (edges) of tetrahedra (triangles)
   // stored in T (analogous to qptoolbox's `outline` and `boundary_faces`).
   //
@@ -132,6 +185,13 @@ const char *__doc_igl_colon = R"igl_Qu8mg5v7(// Colon operator like matlab's col
   //     than hi, vice versa if hi<low
   // Output:
   //   I  list of values from low to hi with step size step)igl_Qu8mg5v7";
+const char *__doc_igl_column_to_quats = R"igl_Qu8mg5v7(// "Columnize" a list of quaternions (q1x,q1y,q1z,q1w,q2x,q2y,q2z,q2w,...)
+  //
+  // Inputs:
+  //   Q  n*4-long list of coefficients
+  // Outputs:
+  //   vQ  n-long list of quaternions
+  // Returns false if n%4!=0)igl_Qu8mg5v7";
 const char *__doc_igl_comb_cross_field = R"igl_Qu8mg5v7(// Inputs:
   //   V          #V by 3 eigen Matrix of mesh vertex 3D positions
   //   F          #F by 4 eigen Matrix of face (quad) indices
@@ -370,6 +430,32 @@ const char *__doc_igl_cut_mesh_from_singularities = R"igl_Qu8mg5v7(// Given a me
   //   seams  #F by 3 list of per corner booleans that denotes if an edge is a
   //     seam or not
   //)igl_Qu8mg5v7";
+const char *__doc_igl_deform_skeleton = R"igl_Qu8mg5v7(// Deform a skeleton.
+  //
+  // Inputs:
+  //   C  #C by 3 list of joint positions
+  //   BE  #BE by 2 list of bone edge indices
+  //   vA  #BE list of bone transformations
+  // Outputs
+  //   CT  #BE*2 by 3 list of deformed joint positions
+  //   BET  #BE by 2 list of bone edge indices (maintains order)
+  //)igl_Qu8mg5v7";
+const char *__doc_igl_directed_edge_orientations = R"igl_Qu8mg5v7(// Determine rotations that take each edge from the x-axis to its given rest
+  // orientation.
+  //
+  // Inputs:
+  //   C  #C by 3 list of edge vertex positions
+  //   E  #E by 2 list of directed edges
+  // Outputs:
+  //   Q  #E list of quaternions 
+  //)igl_Qu8mg5v7";
+const char *__doc_igl_directed_edge_parents = R"igl_Qu8mg5v7(// Recover "parents" (preceeding edges) in a tree given just directed edges.
+  //
+  // Inputs:
+  //   E  #E by 2 list of directed edges
+  // Outputs:
+  //   P  #E list of parent indices into E (-1) means root
+  //)igl_Qu8mg5v7";
 const char *__doc_igl_doublearea = R"igl_Qu8mg5v7(// DOUBLEAREA computes twice the area for each input triangle[quad]
   //
   // Templates:
@@ -398,6 +484,15 @@ const char *__doc_igl_doublearea_quad = R"igl_Qu8mg5v7(// DOUBLEAREA_QUAD comput
   // Outputs:
   //   dblA  #F list of quadrilateral double areas
   //)igl_Qu8mg5v7";
+const char *__doc_igl_dqs = R"igl_Qu8mg5v7(// Dual quaternion skinning
+  //
+  // Inputs:
+  //   V  #V by 3 list of rest positions
+  //   W  #W by #C list of weights
+  //   vQ  #C list of rotation quaternions 
+  //   vT  #C list of translation vectors
+  // Outputs:
+  //   U  #V by 3 list of new positions)igl_Qu8mg5v7";
 const char *__doc_igl_edge_lengths = R"igl_Qu8mg5v7(// Constructs a list of lengths of edges opposite each index in a face
   // (triangle/tet) list
   //
@@ -455,6 +550,23 @@ const char *__doc_igl_embree_reorient_facets_raycast = R"igl_Qu8mg5v7(// Orient
     // Outputs:
     //   I  #F list of whether face has been flipped
     //   C  #F list of patch ID (output of bfs_orient > manifold patches))igl_Qu8mg5v7";
+const char *__doc_igl_embree_line_mesh_intersection = R"igl_Qu8mg5v7(// Project the point cloud V_source onto the triangle mesh
+    // V_target,F_target. 
+    // A ray is casted for every vertex in the direction specified by 
+    // N_source and its opposite.
+    //
+    // Input:
+    // V_source: #Vx3 Vertices of the source mesh
+    // N_source: #Vx3 Normals of the point cloud
+    // V_target: #V2x3 Vertices of the target mesh
+    // F_target: #F2x3 Faces of the target mesh
+    //
+    // Output:
+    // #Vx3 matrix of baricentric coordinate. Each row corresponds to 
+    // a vertex of the projected mesh and it has the following format:
+    // id b1 b2. id is the id of a face of the source mesh. b1 and b2 are 
+    // the barycentric coordinates wrt the first two edges of the triangle
+    // To convert to standard global coordinates, see barycentric_to_global.h)igl_Qu8mg5v7";
 const char *__doc_igl_find_cross_field_singularities = R"igl_Qu8mg5v7(// Inputs:
   //   V                #V by 3 eigen Matrix of mesh vertex 3D positions
   //   F                #F by 3 eigen Matrix of face (quad) indices
@@ -493,6 +605,18 @@ const char *__doc_igl_floor = R"igl_Qu8mg5v7(// Floor a given matrix to nearest
   //   X  m by n matrix of scalars
   // Outputs:
   //   Y  m by n matrix of floored integers)igl_Qu8mg5v7";
+const char *__doc_igl_forward_kinematics = R"igl_Qu8mg5v7(// Given a skeleton and a set of relative bone rotations compute absolute
+  // rigid transformations for each bone.
+  //
+  // Inputs:
+  //   C  #C by dim list of joint positions
+  //   BE  #BE by 2 list of bone edge indices
+  //   P  #BE list of parent indices into BE
+  //   dQ  #BE list of relative rotations
+  //   dT  #BE list of relative translations
+  // Outputs:
+  //   vQ  #BE list of absolute rotations
+  //   vT  #BE list of absolute translations)igl_Qu8mg5v7";
 const char *__doc_igl_gaussian_curvature = R"igl_Qu8mg5v7(// Compute discrete local integral gaussian curvature (angle deficit, without
   // averaging by local area).
   //
@@ -591,6 +715,39 @@ const char *__doc_igl_jet = R"igl_Qu8mg5v7(// JET like MATLAB's jet
   //   r  red value
   //   g  green value
   //   b  blue value)igl_Qu8mg5v7";
+const char *__doc_igl_lbs_matrix = R"igl_Qu8mg5v7(// LBS_MATRIX Linear blend skinning can be expressed by V' = M * T where V' is
+  // a #V by dim matrix of deformed vertex positions (one vertex per row), M is a
+  // #V by (dim+1)*#T (composed of weights and rest positions) and T is a
+  // #T*(dim+1) by dim matrix of #T stacked transposed transformation matrices.
+  // See equations (1) and (2) in "Fast Automatic Skinning Transformations"
+  // [Jacobson et al 2012]
+  //
+  // Inputs:
+  //   V  #V by dim list of rest positions
+  //   W  #V+ by #T  list of weights
+  // Outputs:
+  //   M  #V by #T*(dim+1)
+  //
+  // In MATLAB:
+  //   kron(ones(1,size(W,2)),[V ones(size(V,1),1)]).*kron(W,ones(1,size(V,2)+1)))igl_Qu8mg5v7";
+const char *__doc_igl_lbs_matrix_column = R"igl_Qu8mg5v7(// LBS_MATRIX  construct a matrix that when multiplied against a column of
+  // affine transformation entries computes new coordinates of the vertices
+  //
+  // I'm not sure it makes since that the result is stored as a sparse matrix.
+  // The number of non-zeros per row *is* dependent on the number of mesh
+  // vertices and handles.
+  //
+  // Inputs:
+  //   V  #V by dim list of vertex rest positions
+  //   W  #V by #handles list of correspondence weights
+  // Output:
+  //   M  #V * dim by #handles * dim * (dim+1) matrix such that
+  //     new_V(:) = LBS(V,W,A) = reshape(M * A,size(V)), where A is a column
+  //     vectors formed by the entries in each handle's dim by dim+1 
+  //     transformation matrix. Specifcally, A =
+  //       reshape(permute(Astack,[3 1 2]),n*dim*(dim+1),1)
+  //     or A = [Lxx;Lyx;Lxy;Lyy;tx;ty], and likewise for other dim
+  //     if Astack(:,:,i) is the dim by (dim+1) transformation at handle i)igl_Qu8mg5v7";
 const char *__doc_igl_local_basis = R"igl_Qu8mg5v7(// Compute a local orthogonal reference system for each triangle in the given mesh
   // Templates:
   //   DerivedV derived from vertex positions matrix type: i.e. MatrixXd
@@ -702,6 +859,22 @@ const char *__doc_igl_n_polyvector = R"igl_Qu8mg5v7(// Inputs:
   // Output:
   //                  3 by 3 rotation matrix that takes v0 to v1
   //)igl_Qu8mg5v7";
+const char *__doc_igl_normalize_row_lengths = R"igl_Qu8mg5v7(// Obsolete: just use A.rowwise().normalize() or B=A.rowwise().normalized();
+  //
+  // Normalize the rows in A so that their lengths are each 1 and place the new
+  // entries in B
+  // Inputs:
+  //   A  #rows by k input matrix
+  // Outputs:
+  //   B  #rows by k input matrix, can be the same as A)igl_Qu8mg5v7";
+const char *__doc_igl_normalize_row_sums = R"igl_Qu8mg5v7(// Normalize the rows in A so that their sums are each 1 and place the new
+  // entries in B
+  // Inputs:
+  //   A  #rows by k input matrix
+  // Outputs:
+  //   B  #rows by k input matrix, can be the same as A
+  //
+  // Note: This is just calling an Eigen one-liner.)igl_Qu8mg5v7";
 const char *__doc_igl_parula = R"igl_Qu8mg5v7(// PARULA like MATLAB's parula
   //
   // Inputs:
@@ -894,6 +1067,23 @@ const char *__doc_igl_readOFF = R"igl_Qu8mg5v7(// Read a mesh from an ascii obj
   //   N  double matrix of corner normals #N by 3
   //   FN  #F list of face indices into vertex normals
   // Returns true on success, false on errors)igl_Qu8mg5v7";
+const char *__doc_igl_readTGF = R"igl_Qu8mg5v7(// READTGF
+  //
+  // [V,E,P,BE,CE,PE] = readTGF(filename)
+  //
+  // Read a graph from a .tgf file
+  //
+  // Input:
+  //  filename  .tgf file name
+  // Ouput:
+  //  V  # vertices by 3 list of vertex positions
+  //  E  # edges by 2 list of edge indices
+  //  P  # point-handles list of point handle indices
+  //  BE # bone-edges by 2 list of bone-edge indices
+  //  CE # cage-edges by 2 list of cage-edge indices
+  //  PE # pseudo-edges by 2 list of pseudo-edge indices
+  // 
+  // Assumes that graph vertices are 3 dimensional)igl_Qu8mg5v7";
 const char *__doc_igl_read_triangle_mesh = R"igl_Qu8mg5v7(// read mesh from an ascii file with automatic detection of file format.
   // supported: obj, off, stl, wrl, ply, mesh)
   // 

+ 15 - 0
python/py_doc.h

@@ -4,11 +4,15 @@ extern const char *__doc_igl_arap_solve;
 extern const char *__doc_igl_avg_edge_length;
 extern const char *__doc_igl_barycenter;
 extern const char *__doc_igl_barycentric_coordinates;
+extern const char *__doc_igl_barycentric_to_global;
+extern const char *__doc_igl_bbw_bbw;
+extern const char *__doc_igl_boundary_conditions;
 extern const char *__doc_igl_boundary_facets;
 extern const char *__doc_igl_boundary_loop;
 extern const char *__doc_igl_cat;
 extern const char *__doc_igl_collapse_edge;
 extern const char *__doc_igl_colon;
+extern const char *__doc_igl_column_to_quats;
 extern const char *__doc_igl_comb_cross_field;
 extern const char *__doc_igl_comb_frame_field;
 extern const char *__doc_igl_compute_frame_field_bisectors;
@@ -23,19 +27,25 @@ extern const char *__doc_igl_cotmatrix;
 extern const char *__doc_igl_covariance_scatter_matrix;
 extern const char *__doc_igl_cross_field_missmatch;
 extern const char *__doc_igl_cut_mesh_from_singularities;
+extern const char *__doc_igl_deform_skeleton;
+extern const char *__doc_igl_directed_edge_orientations;
+extern const char *__doc_igl_directed_edge_parents;
 extern const char *__doc_igl_doublearea;
 extern const char *__doc_igl_doublearea_single;
 extern const char *__doc_igl_doublearea_quad;
+extern const char *__doc_igl_dqs;
 extern const char *__doc_igl_edge_lengths;
 extern const char *__doc_igl_edge_topology;
 extern const char *__doc_igl_eigs;
 extern const char *__doc_igl_embree_ambient_occlusion;
 extern const char *__doc_igl_embree_reorient_facets_raycast;
+extern const char *__doc_igl_embree_line_mesh_intersection;
 extern const char *__doc_igl_find_cross_field_singularities;
 extern const char *__doc_igl_fit_rotations;
 extern const char *__doc_igl_fit_rotations_planar;
 extern const char *__doc_igl_fit_rotations_SSE;
 extern const char *__doc_igl_floor;
+extern const char *__doc_igl_forward_kinematics;
 extern const char *__doc_igl_gaussian_curvature;
 extern const char *__doc_igl_get_seconds;
 extern const char *__doc_igl_grad;
@@ -45,6 +55,8 @@ extern const char *__doc_igl_internal_angles;
 extern const char *__doc_igl_invert_diag;
 extern const char *__doc_igl_is_irregular_vertex;
 extern const char *__doc_igl_jet;
+extern const char *__doc_igl_lbs_matrix;
+extern const char *__doc_igl_lbs_matrix_column;
 extern const char *__doc_igl_local_basis;
 extern const char *__doc_igl_lscm;
 extern const char *__doc_igl_map_vertices_to_circle;
@@ -53,6 +65,8 @@ extern const char *__doc_igl_min_quad_with_fixed_precompute;
 extern const char *__doc_igl_min_quad_with_fixed_solve;
 extern const char *__doc_igl_min_quad_with_fixed;
 extern const char *__doc_igl_n_polyvector;
+extern const char *__doc_igl_normalize_row_lengths;
+extern const char *__doc_igl_normalize_row_sums;
 extern const char *__doc_igl_parula;
 extern const char *__doc_igl_per_corner_normals;
 extern const char *__doc_igl_per_edge_normals;
@@ -71,6 +85,7 @@ extern const char *__doc_igl_readDMAT;
 extern const char *__doc_igl_readMESH;
 extern const char *__doc_igl_readOBJ;
 extern const char *__doc_igl_readOFF;
+extern const char *__doc_igl_readTGF;
 extern const char *__doc_igl_read_triangle_mesh;
 extern const char *__doc_igl_remove_duplicate_vertices;
 extern const char *__doc_igl_rotate_vectors;

+ 27 - 0
python/py_igl.cpp

@@ -1,6 +1,7 @@
 #include <Eigen/Dense>
 
 #include "python_shared.h"
+#include "modules/py_typedefs.h"
 
 #include <igl/AABB.h>
 #include <igl/ARAPEnergyType.h>
@@ -11,11 +12,14 @@
 #include <igl/avg_edge_length.h>
 #include <igl/barycenter.h>
 #include <igl/barycentric_coordinates.h>
+#include <igl/barycentric_to_global.h>
+#include <igl/boundary_conditions.h>
 #include <igl/boundary_facets.h>
 #include <igl/boundary_loop.h>
 #include <igl/cat.h>
 #include <igl/collapse_edge.h>
 #include <igl/colon.h>
+#include <igl/column_to_quats.h>
 #include <igl/comb_cross_field.h>
 #include <igl/comb_frame_field.h>
 #include <igl/compute_frame_field_bisectors.h>
@@ -23,13 +27,18 @@
 #include <igl/covariance_scatter_matrix.h>
 #include <igl/cross_field_missmatch.h>
 #include <igl/cut_mesh_from_singularities.h>
+#include <igl/deform_skeleton.h>
+#include <igl/directed_edge_orientations.h>
+#include <igl/directed_edge_parents.h>
 #include <igl/doublearea.h>
+#include <igl/dqs.h>
 #include <igl/edge_lengths.h>
 #include <igl/edge_topology.h>
 #include <igl/eigs.h>
 #include <igl/find_cross_field_singularities.h>
 #include <igl/fit_rotations.h>
 #include <igl/floor.h>
+#include <igl/forward_kinematics.h>
 #include <igl/gaussian_curvature.h>
 #include <igl/get_seconds.h>
 #include <igl/grad.h>
@@ -39,12 +48,15 @@
 #include <igl/invert_diag.h>
 #include <igl/is_irregular_vertex.h>
 #include <igl/jet.h>
+#include <igl/lbs_matrix.h>
 #include <igl/local_basis.h>
 #include <igl/lscm.h>
 #include <igl/map_vertices_to_circle.h>
 #include <igl/massmatrix.h>
 #include <igl/min_quad_with_fixed.h>
 #include <igl/n_polyvector.h>
+#include <igl/normalize_row_lengths.h>
+#include <igl/normalize_row_sums.h>
 #include <igl/parula.h>
 #include <igl/per_corner_normals.h>
 #include <igl/per_edge_normals.h>
@@ -60,6 +72,7 @@
 #include <igl/readMESH.h>
 #include <igl/readOBJ.h>
 #include <igl/readOFF.h>
+#include <igl/readTGF.h>
 #include <igl/read_triangle_mesh.h>
 #include <igl/remove_duplicate_vertices.h>
 #include <igl/rotate_vectors.h>
@@ -82,6 +95,8 @@
 
 void python_export_igl(py::module &m)
 {
+#include "modules/py_typedefs.cpp"
+
 #include "py_igl/py_AABB.cpp"
 #include "py_igl/py_ARAPEnergyType.cpp"
 #include "py_igl/py_MeshBooleanType.cpp"
@@ -91,11 +106,14 @@ void python_export_igl(py::module &m)
 #include "py_igl/py_avg_edge_length.cpp"
 #include "py_igl/py_barycenter.cpp"
 #include "py_igl/py_barycentric_coordinates.cpp"
+#include "py_igl/py_barycentric_to_global.cpp"
+#include "py_igl/py_boundary_conditions.cpp"
 #include "py_igl/py_boundary_facets.cpp"
 #include "py_igl/py_boundary_loop.cpp"
 #include "py_igl/py_cat.cpp"
 #include "py_igl/py_collapse_edge.cpp"
 #include "py_igl/py_colon.cpp"
+#include "py_igl/py_column_to_quats.cpp"
 #include "py_igl/py_comb_cross_field.cpp"
 #include "py_igl/py_comb_frame_field.cpp"
 #include "py_igl/py_compute_frame_field_bisectors.cpp"
@@ -103,13 +121,18 @@ void python_export_igl(py::module &m)
 #include "py_igl/py_covariance_scatter_matrix.cpp"
 #include "py_igl/py_cross_field_missmatch.cpp"
 #include "py_igl/py_cut_mesh_from_singularities.cpp"
+#include "py_igl/py_deform_skeleton.cpp"
+#include "py_igl/py_directed_edge_orientations.cpp"
+#include "py_igl/py_directed_edge_parents.cpp"
 #include "py_igl/py_doublearea.cpp"
+#include "py_igl/py_dqs.cpp"
 #include "py_igl/py_edge_lengths.cpp"
 #include "py_igl/py_edge_topology.cpp"
 #include "py_igl/py_eigs.cpp"
 #include "py_igl/py_find_cross_field_singularities.cpp"
 #include "py_igl/py_fit_rotations.cpp"
 #include "py_igl/py_floor.cpp"
+#include "py_igl/py_forward_kinematics.cpp"
 #include "py_igl/py_gaussian_curvature.cpp"
 #include "py_igl/py_get_seconds.cpp"
 #include "py_igl/py_grad.cpp"
@@ -119,12 +142,15 @@ void python_export_igl(py::module &m)
 #include "py_igl/py_invert_diag.cpp"
 #include "py_igl/py_is_irregular_vertex.cpp"
 #include "py_igl/py_jet.cpp"
+#include "py_igl/py_lbs_matrix.cpp"
 #include "py_igl/py_local_basis.cpp"
 #include "py_igl/py_lscm.cpp"
 #include "py_igl/py_map_vertices_to_circle.cpp"
 #include "py_igl/py_massmatrix.cpp"
 #include "py_igl/py_min_quad_with_fixed.cpp"
 #include "py_igl/py_n_polyvector.cpp"
+#include "py_igl/py_normalize_row_lengths.cpp"
+#include "py_igl/py_normalize_row_sums.cpp"
 #include "py_igl/py_parula.cpp"
 #include "py_igl/py_per_corner_normals.cpp"
 #include "py_igl/py_per_edge_normals.cpp"
@@ -140,6 +166,7 @@ void python_export_igl(py::module &m)
 #include "py_igl/py_readMESH.cpp"
 #include "py_igl/py_readOBJ.cpp"
 #include "py_igl/py_readOFF.cpp"
+#include "py_igl/py_readTGF.cpp"
 #include "py_igl/py_read_triangle_mesh.cpp"
 #include "py_igl/py_remove_duplicate_vertices.cpp"
 #include "py_igl/py_rotate_vectors.cpp"

+ 42 - 0
python/py_igl/bbw/py_bbw.cpp

@@ -0,0 +1,42 @@
+py::enum_<igl::bbw::QPSolver>(m, "QPSolver")
+    .value("QP_SOLVER_IGL_ACTIVE_SET", igl::bbw::QP_SOLVER_IGL_ACTIVE_SET)
+    .value("QP_SOLVER_MOSEK", igl::bbw::QP_SOLVER_MOSEK)
+    .value("NUM_QP_SOLVERS", igl::bbw::NUM_QP_SOLVERS)
+    .export_values();
+
+// Wrap the BBWData class
+py::class_<igl::bbw::BBWData > BBWData(m, "BBWData");
+
+BBWData
+.def(py::init<>())
+.def_readwrite("partition_unity", &igl::bbw::BBWData::partition_unity)
+.def_readwrite("W0", &igl::bbw::BBWData::W0)
+.def_readwrite("active_set_params", &igl::bbw::BBWData::active_set_params)
+.def_readwrite("qp_solver", &igl::bbw::BBWData::qp_solver)
+.def_readwrite("verbosity", &igl::bbw::BBWData::verbosity)
+#ifndef IGL_NO_MOSEK
+.def_readwrite("mosek_data", &igl::bbw::BBWData::mosek_data)
+#endif
+.def("print", [](igl::bbw::BBWData& data)
+{
+    return data.print();
+})
+;
+
+m.def("bbw", []
+(
+  const Eigen::MatrixXd& V,
+  const Eigen::MatrixXi& Ele,
+  const Eigen::MatrixXi& b,
+  const Eigen::MatrixXd& bc,
+  igl::bbw::BBWData& data,
+  Eigen::MatrixXd& W
+)
+{
+  assert_is_VectorX("b",b);
+  Eigen::VectorXi bv;
+  if (b.size() != 0)
+    bv = b;
+  return igl::bbw::bbw(V, Ele, bv, bc, data, W);
+}, __doc_igl_bbw_bbw,
+py::arg("V"), py::arg("Ele"), py::arg("b"), py::arg("bc"), py::arg("data"), py::arg("W"));

+ 13 - 0
python/py_igl/embree/py_line_mesh_intersection.cpp

@@ -0,0 +1,13 @@
+
+
+m.def("line_mesh_intersection", []
+(
+  const Eigen::MatrixXd& V_source,
+  const Eigen::MatrixXd& N_source,
+  const Eigen::MatrixXd& V_target,
+  const Eigen::MatrixXi& F_target
+)
+{
+  return igl::embree::line_mesh_intersection(V_source, N_source, V_target, F_target);
+}, __doc_igl_embree_line_mesh_intersection,
+py::arg("V_source"), py::arg("N_source"), py::arg("V_target"), py::arg("F_target"));

+ 12 - 0
python/py_igl/py_barycentric_to_global.cpp

@@ -0,0 +1,12 @@
+
+
+m.def("barycentric_to_global", []
+(
+  const Eigen::MatrixXd& V,
+  const Eigen::MatrixXi& F,
+  const Eigen::MatrixXd& bc
+)
+{
+  return igl::barycentric_to_global(V, F, bc);
+}, __doc_igl_barycentric_to_global,
+py::arg("V"), py::arg("F"), py::arg("bc"));

+ 24 - 0
python/py_igl/py_boundary_conditions.cpp

@@ -0,0 +1,24 @@
+
+
+m.def("boundary_conditions", []
+(
+  const Eigen::MatrixXd& V,
+  const Eigen::MatrixXi& Ele,
+  const Eigen::MatrixXd& C,
+  const Eigen::MatrixXi& P,
+  const Eigen::MatrixXi& BE,
+  const Eigen::MatrixXi& CE,
+  Eigen::MatrixXi& b,
+  Eigen::MatrixXd& bc
+)
+{
+  assert_is_VectorX("P", P);
+  Eigen::VectorXi Pv;
+  if (P.size() != 0)
+    Pv = P;
+  Eigen::VectorXi bv;
+  igl::boundary_conditions(V, Ele, C, Pv, BE, CE, bv, bc);
+  b = bv;
+}, __doc_igl_boundary_conditions,
+py::arg("V"), py::arg("Ele"), py::arg("C"), py::arg("P"), py::arg("BE"), py::arg("CE"), py::arg("b"), py::arg("bc"));
+

+ 10 - 0
python/py_igl/py_column_to_quats.cpp

@@ -0,0 +1,10 @@
+m.def("column_to_quats", []
+(
+  const Eigen::MatrixXd& Q,
+  RotationList& vQ
+)
+{
+  return igl::column_to_quats(Q, vQ);
+}, __doc_igl_column_to_quats,
+py::arg("Q"), py::arg("vQ"));
+

+ 36 - 0
python/py_igl/py_deform_skeleton.cpp

@@ -0,0 +1,36 @@
+// COMPLETE BINDINGS ========================
+
+
+m.def("deform_skeleton", []
+(
+  const Eigen::MatrixXd& C,
+  const Eigen::MatrixXi& BE,
+  const Eigen::MatrixXd& T,
+  Eigen::MatrixXd& CT,
+  Eigen::MatrixXi& BET
+)
+{
+  return igl::deform_skeleton(C, BE, T, CT, BET);
+}, __doc_igl_deform_skeleton,
+py::arg("C"), py::arg("BE"), py::arg("T"), py::arg("CT"), py::arg("BET"));
+
+
+
+
+
+// INCOMPLETE BINDINGS ========================
+
+
+//m.def("deform_skeleton", []
+//(
+//  const Eigen::MatrixXd& C,
+//  const Eigen::MatrixXi& BE,
+//  std::vector<Eigen::Affine3d, Eigen::aligned_allocator<Eigen::Affine3d> > & vA,
+//  Eigen::MatrixXd& CT,
+//  Eigen::MatrixXi& BET
+//)
+//{
+//  return igl::deform_skeleton(C, BE, vA, CT, BET);
+//}, __doc_igl_deform_skeleton,
+//py::arg("C"), py::arg("BE"), py::arg("vA"), py::arg("CT"), py::arg("BET"));
+

+ 12 - 0
python/py_igl/py_directed_edge_orientations.cpp

@@ -0,0 +1,12 @@
+
+m.def("directed_edge_orientations", []
+(
+  const Eigen::MatrixXd& C,
+  const Eigen::MatrixXi& E,
+  RotationList& Q
+)
+{
+  return igl::directed_edge_orientations(C, E, Q);
+}, __doc_igl_directed_edge_orientations,
+py::arg("C"), py::arg("E"), py::arg("Q"));
+

+ 14 - 0
python/py_igl/py_directed_edge_parents.cpp

@@ -0,0 +1,14 @@
+
+
+m.def("directed_edge_parents", []
+(
+  const Eigen::MatrixXi& E,
+  Eigen::MatrixXi& P
+)
+{
+  Eigen::VectorXi Pv;
+  igl::directed_edge_parents(E, Pv);
+  P = Pv;
+}, __doc_igl_directed_edge_parents,
+py::arg("E"), py::arg("P"));
+

+ 21 - 0
python/py_igl/py_dqs.cpp

@@ -0,0 +1,21 @@
+
+
+m.def("dqs", []
+(
+  const Eigen::MatrixXd& V,
+  const Eigen::MatrixXd& W,
+  const RotationList& vQ,
+  const std::vector<Eigen::MatrixXd> & vT,
+  Eigen::MatrixXd& U
+)
+{
+  std::vector<Eigen::Vector3d> vTv;
+  for (auto item : vT) {
+    assert_is_Vector3("item", item);
+    Eigen::Vector3d obj = Eigen::Vector3d(item);
+    vTv.push_back(obj);
+  }
+  return igl::dqs(V, W, vQ, vTv, U);
+}, __doc_igl_dqs,
+py::arg("V"), py::arg("W"), py::arg("vQ"), py::arg("vT"), py::arg("U"));
+

+ 62 - 0
python/py_igl/py_forward_kinematics.cpp

@@ -0,0 +1,62 @@
+
+//m.def("forward_kinematics", []
+//(
+//  const Eigen::MatrixXd& C,
+//  const Eigen::MatrixXi& BE,
+//  const Eigen::MatrixXi& P,
+//  std::vector<Eigen::Quaterniond, Eigen::aligned_allocator<Eigen::Quaterniond> > & dQ,
+//  std::vector<Eigen::Vector3d> & dT,
+//  std::vector<Eigen::Quaterniond, Eigen::aligned_allocator<Eigen::Quaterniond> > & vQ,
+//  std::vector<Eigen::Vector3d> & vT
+//)
+//{
+//  return igl::forward_kinematics(C, BE, P, dQ, dT, vQ, vT);
+//}, __doc_igl_forward_kinematics,
+//py::arg("C"), py::arg("BE"), py::arg("P"), py::arg("dQ"), py::arg("dT"), py::arg("vQ"), py::arg("vT"));
+
+m.def("forward_kinematics", []
+(
+  const Eigen::MatrixXd& C,
+  const Eigen::MatrixXi& BE,
+  const Eigen::MatrixXi& P,
+  const RotationList& dQ,
+  RotationList& vQ,
+  py::list vT
+)
+{
+  std::vector<Eigen::Vector3d> vTl;
+  igl::forward_kinematics(C, BE, P, dQ, vQ, vTl);
+  for (auto item : vTl) {
+    py::object obj = py::cast(Eigen::MatrixXd(item));
+    vT.append(obj);
+  }
+}, __doc_igl_forward_kinematics,
+py::arg("C"), py::arg("BE"), py::arg("P"), py::arg("dQ"), py::arg("vQ"), py::arg("vT"));
+
+//m.def("forward_kinematics", []
+//(
+//  const Eigen::MatrixXd& C,
+//  const Eigen::MatrixXi& BE,
+//  const Eigen::MatrixXi& P,
+//  std::vector<Eigen::Quaterniond, Eigen::aligned_allocator<Eigen::Quaterniond> > & dQ,
+//  std::vector<Eigen::Vector3d> & dT,
+//  Eigen::MatrixXd& T
+//)
+//{
+//  return igl::forward_kinematics(C, BE, P, dQ, dT, T);
+//}, __doc_igl_forward_kinematics,
+//py::arg("C"), py::arg("BE"), py::arg("P"), py::arg("dQ"), py::arg("dT"), py::arg("T"));
+
+//m.def("forward_kinematics", []
+//(
+//  const Eigen::MatrixXd& C,
+//  const Eigen::MatrixXi& BE,
+//  const Eigen::MatrixXi& P,
+//  std::vector<Eigen::Quaterniond, Eigen::aligned_allocator<Eigen::Quaterniond> > & dQ,
+//  Eigen::MatrixXd& T
+//)
+//{
+//  return igl::forward_kinematics(C, BE, P, dQ, T);
+//}, __doc_igl_forward_kinematics,
+//py::arg("C"), py::arg("BE"), py::arg("P"), py::arg("dQ"), py::arg("T"));
+

+ 67 - 0
python/py_igl/py_lbs_matrix.cpp

@@ -0,0 +1,67 @@
+// COMPLETE BINDINGS ========================
+
+
+m.def("lbs_matrix", []
+(
+  const Eigen::MatrixXd& V,
+  const Eigen::MatrixXd& W,
+  Eigen::MatrixXd& M
+)
+{
+  return igl::lbs_matrix(V, W, M);
+}, __doc_igl_lbs_matrix,
+py::arg("V"), py::arg("W"), py::arg("M"));
+
+m.def("lbs_matrix_column", []
+(
+  const Eigen::MatrixXd& V,
+  const Eigen::MatrixXd& W,
+  Eigen::MatrixXd& M
+)
+{
+  return igl::lbs_matrix_column(V, W, M);
+}, __doc_igl_lbs_matrix_column,
+py::arg("V"), py::arg("W"), py::arg("M"));
+
+m.def("lbs_matrix_column", []
+(
+  const Eigen::MatrixXd& V,
+  const Eigen::MatrixXd& W,
+  const Eigen::MatrixXi& WI,
+  Eigen::MatrixXd& M
+)
+{
+  return igl::lbs_matrix_column(V, W, WI, M);
+}, __doc_igl_lbs_matrix_column,
+py::arg("V"), py::arg("W"), py::arg("WI"), py::arg("M"));
+
+
+
+
+
+// INCOMPLETE BINDINGS ========================
+
+
+m.def("lbs_matrix_column", []
+(
+  const Eigen::MatrixXd& V,
+  const Eigen::MatrixXd& W,
+  Eigen::SparseMatrix<double>& M
+)
+{
+  return igl::lbs_matrix_column(V, W, M);
+}, __doc_igl_lbs_matrix_column,
+py::arg("V"), py::arg("W"), py::arg("M"));
+
+m.def("lbs_matrix_column", []
+(
+  const Eigen::MatrixXd& V,
+  const Eigen::MatrixXd& W,
+  const Eigen::MatrixXi& WI,
+  Eigen::SparseMatrix<double>& M
+)
+{
+  return igl::lbs_matrix_column(V, W, WI, M);
+}, __doc_igl_lbs_matrix_column,
+py::arg("V"), py::arg("W"), py::arg("WI"), py::arg("M"));
+

+ 12 - 0
python/py_igl/py_normalize_row_lengths.cpp

@@ -0,0 +1,12 @@
+
+
+m.def("normalize_row_lengths", []
+(
+  const Eigen::MatrixXd& A,
+  Eigen::MatrixXd& B
+)
+{
+  return igl::normalize_row_lengths(A, B);
+}, __doc_igl_normalize_row_lengths,
+py::arg("A"), py::arg("B"));
+

+ 12 - 0
python/py_igl/py_normalize_row_sums.cpp

@@ -0,0 +1,12 @@
+
+
+m.def("normalize_row_sums", []
+(
+  const Eigen::MatrixXd& A,
+  Eigen::MatrixXd& B
+)
+{
+  return igl::normalize_row_sums(A, B);
+}, __doc_igl_normalize_row_sums,
+py::arg("A"), py::arg("B"));
+

+ 54 - 0
python/py_igl/py_readTGF.cpp

@@ -0,0 +1,54 @@
+// COMPLETE BINDINGS ========================
+
+
+m.def("readTGF", []
+(
+  const std::string tgf_filename,
+  Eigen::MatrixXd& C,
+  Eigen::MatrixXi& E,
+  Eigen::MatrixXi& P,
+  Eigen::MatrixXi& BE,
+  Eigen::MatrixXi& CE,
+  Eigen::MatrixXi& PE
+)
+{
+  Eigen::VectorXi Pv;
+  bool ret = igl::readTGF(tgf_filename, C, E, Pv, BE, CE, PE);
+  P = Pv;
+  return ret;
+}, __doc_igl_readTGF,
+py::arg("tgf_filename"), py::arg("C"), py::arg("E"), py::arg("P"), py::arg("BE"), py::arg("CE"), py::arg("PE"));
+
+m.def("readTGF", []
+(
+  const std::string tgf_filename,
+  Eigen::MatrixXd& C,
+  Eigen::MatrixXi& E
+)
+{
+  return igl::readTGF(tgf_filename, C, E);
+}, __doc_igl_readTGF,
+py::arg("tgf_filename"), py::arg("C"), py::arg("E"));
+
+
+
+
+
+// INCOMPLETE BINDINGS ========================
+
+
+//m.def("readTGF", []
+//(
+//  const std::string tgf_filename,
+//  std::vector<std::vector<double> > & C,
+//  std::vector<std::vector<int> > & E,
+//  std::vector<int> & P,
+//  std::vector<std::vector<int> > & BE,
+//  std::vector<std::vector<int> > & CE,
+//  std::vector<std::vector<int> > & PE
+//)
+//{
+//  return igl::readTGF(tgf_filename, C, E, P, BE, CE, PE);
+//}, __doc_igl_readTGF,
+//py::arg("tgf_filename"), py::arg("C"), py::arg("E"), py::arg("P"), py::arg("BE"), py::arg("CE"), py::arg("PE"));
+

+ 25 - 4
python/python_shared.cpp

@@ -30,12 +30,16 @@ extern void python_export_igl_triangle(py::module &);
 extern void python_export_igl_cgal(py::module &);
 #endif
 
+#ifdef PY_COPYLEFT
+extern void python_export_igl_copyleft(py::module &);
+#endif
+
 #ifdef PY_PNG
 extern void python_export_igl_png(py::module &);
 #endif
 
-#ifdef PY_COPYLEFT
-extern void python_export_igl_copyleft(py::module &);
+#ifdef PY_BBW
+extern void python_export_igl_bbw(py::module &);
 #endif
 
 PYBIND11_PLUGIN(pyigl) {
@@ -57,11 +61,15 @@ PYBIND11_PLUGIN(pyigl) {
            avg_edge_length
            barycenter
            barycentric_coordinates
+           barycentric_to_global
+           bbw_bbw
+           boundary_conditions
            boundary_facets
            boundary_loop
            cat
            collapse_edge
            colon
+           column_to_quats
            comb_cross_field
            comb_frame_field
            compute_frame_field_bisectors
@@ -77,7 +85,11 @@ PYBIND11_PLUGIN(pyigl) {
            covariance_scatter_matrix
            cross_field_missmatch
            cut_mesh_from_singularities
+           deform_skeleton
+           directed_edge_orientations
+           directed_edge_parents
            doublearea
+           dqs
            edge_lengths
            edge_topology
            eigs
@@ -86,6 +98,7 @@ PYBIND11_PLUGIN(pyigl) {
            find_cross_field_singularities
            fit_rotations
            floor
+           forward_kinematics
            gaussian_curvature
            get_seconds
            grad
@@ -95,12 +108,15 @@ PYBIND11_PLUGIN(pyigl) {
            invert_diag
            is_irregular_vertex
            jet
+           lbs_matrix
            local_basis
            lscm
            map_vertices_to_circle
            massmatrix
            min_quad_with_fixed
            n_polyvector
+           normalize_row_lengths
+           normalize_row_sums
            parula
            per_corner_normals
            per_edge_normals
@@ -118,6 +134,7 @@ PYBIND11_PLUGIN(pyigl) {
            readMESH
            readOBJ
            readOFF
+           readTGF
            read_triangle_mesh
            remove_duplicate_vertices
            rotate_vectors
@@ -168,12 +185,16 @@ PYBIND11_PLUGIN(pyigl) {
     python_export_igl_cgal(m);
     #endif
 
+    #ifdef PY_COPYLEFT
+    python_export_igl_copyleft(m);
+    #endif
+
     #ifdef PY_PNG
     python_export_igl_png(m);
     #endif
 
-    #ifdef PY_COPYLEFT
-    python_export_igl_copyleft(m);
+    #ifdef PY_BBW
+    python_export_igl_bbw(m);
     #endif
 
     return m.ptr();

+ 3 - 0
python/scripts/py_igl.mako

@@ -1,6 +1,7 @@
 #include <Eigen/Dense>
 
 #include "python_shared.h"
+#include "modules/py_typedefs.h"
 
 % for f in functions:
 #include <igl/${f}.h>
@@ -9,6 +10,8 @@
 
 void python_export_igl(py::module &m)
 {
+#include "modules/py_typedefs.cpp"
+
 % for f in functions:
 #include "py_igl/py_${f}.cpp"
 % endfor

+ 12 - 4
python/scripts/python_shared.mako

@@ -30,12 +30,16 @@ extern void python_export_igl_triangle(py::module &);
 extern void python_export_igl_cgal(py::module &);
 #endif
 
+#ifdef PY_COPYLEFT
+extern void python_export_igl_copyleft(py::module &);
+#endif
+
 #ifdef PY_PNG
 extern void python_export_igl_png(py::module &);
 #endif
 
-#ifdef PY_COPYLEFT
-extern void python_export_igl_copyleft(py::module &);
+#ifdef PY_BBW
+extern void python_export_igl_bbw(py::module &);
 #endif
 
 PYBIND11_PLUGIN(pyigl) {
@@ -82,12 +86,16 @@ PYBIND11_PLUGIN(pyigl) {
     python_export_igl_cgal(m);
     #endif
 
+    #ifdef PY_COPYLEFT
+    python_export_igl_copyleft(m);
+    #endif
+
     #ifdef PY_PNG
     python_export_igl_png(m);
     #endif
 
-    #ifdef PY_COPYLEFT
-    python_export_igl_copyleft(m);
+    #ifdef PY_BBW
+    python_export_igl_bbw(m);
     #endif
 
     return m.ptr();

+ 2 - 2
python/tutorial/402_PolyharmonicDeformation.py

@@ -93,8 +93,8 @@ viewer = igl.viewer.Viewer()
 viewer.data.set_mesh(U, F)
 viewer.core.show_lines = False
 viewer.data.set_colors(C)
-# viewer.core.trackball_angle = igl.eigen.Quaterniond(0.81,-0.58,-0.03,-0.03)
-# viewer.core.trackball_angle.normalize()
+viewer.core.trackball_angle = igl.eigen.Quaterniond(0.81,-0.58,-0.03,-0.03)
+viewer.core.trackball_angle.normalize()
 viewer.callback_pre_draw = pre_draw
 viewer.callback_key_down = key_down
 viewer.core.is_animating = True

+ 145 - 0
python/tutorial/403_BoundedBiharmonicWeights.py

@@ -0,0 +1,145 @@
+import sys, os
+
+# Add the igl library to the modules search path
+sys.path.insert(0, os.getcwd() + "/../")
+import pyigl as igl
+
+from shared import TUTORIAL_SHARED_PATH, check_dependencies, print_usage
+
+dependencies = ["viewer", "bbw"]
+check_dependencies(dependencies)
+
+
+def pre_draw(viewer):
+    global pose, anim_t, C, BE, P, U, M, anim_t_dir
+
+    if viewer.core.is_animating:
+        # Interpolate pose and identity
+        anim_pose = igl.RotationList(len(pose))
+
+        for e in range(len(pose)):
+            anim_pose[e] = pose[e].slerp(anim_t, igl.eigen.Quaterniond.Identity())
+
+        # Propogate relative rotations via FK to retrieve absolute transformations
+        vQ = igl.RotationList()
+        vT = []
+        igl.forward_kinematics(C, BE, P, anim_pose, vQ, vT)
+        dim = C.cols()
+        T = igl.eigen.MatrixXd(BE.rows() * (dim + 1), dim)
+        for e in range(BE.rows()):
+            a = igl.eigen.Affine3d.Identity()
+            a.translate(vT[e])
+            a.rotate(vQ[e])
+            T.setBlock(e * (dim + 1), 0, dim + 1, dim, a.matrix().transpose().block(0, 0, dim + 1, dim))
+
+        # Compute deformation via LBS as matrix multiplication
+        U = M * T
+
+        # Also deform skeleton edges
+        CT = igl.eigen.MatrixXd()
+        BET = igl.eigen.MatrixXi()
+        igl.deform_skeleton(C, BE, T, CT, BET)
+
+        viewer.data.set_vertices(U)
+        viewer.data.set_edges(CT, BET, sea_green)
+        viewer.data.compute_normals()
+        anim_t += anim_t_dir
+        anim_t_dir *= -1.0 if (0.0 >= anim_t or anim_t >= 1.0) else 1.0
+
+    return False
+
+
+def key_down(viewer, key, mods):
+    global selected, W
+    if key == ord('.'):
+        selected += 1
+        selected = min(max(selected, 0), W.cols()-1)
+        set_color(viewer)
+    elif key == ord(','):
+        selected -= 1
+        selected = min(max(selected, 0), W.cols()-1)
+        set_color(viewer)
+    elif key == ord(' '):
+        viewer.core.is_animating = not viewer.core.is_animating
+
+    return True
+
+
+def set_color(viewer):
+    global selected, W
+    C = igl.eigen.MatrixXd()
+    igl.jet(W.col(selected), True, C)
+    viewer.data.set_colors(C)
+
+
+if __name__ == "__main__":
+    keys = {".": "show next weight function",
+            ",": "show previous weight function",
+            "space": "toggle animation"}
+
+    print_usage(keys)
+
+    V = igl.eigen.MatrixXd()
+    W = igl.eigen.MatrixXd()
+    U = igl.eigen.MatrixXd()
+    C = igl.eigen.MatrixXd()
+    M = igl.eigen.MatrixXd()
+    Q = igl.eigen.MatrixXd()
+    T = igl.eigen.MatrixXi()
+    F = igl.eigen.MatrixXi()
+    BE = igl.eigen.MatrixXi()
+    P = igl.eigen.MatrixXi()
+
+    sea_green = igl.eigen.MatrixXd([[70. / 255., 252. / 255., 167. / 255.]])
+
+    selected = 0
+    pose = igl.RotationList()
+    anim_t = 1.0
+    anim_t_dir = -0.03
+
+    igl.readMESH(TUTORIAL_SHARED_PATH + "hand.mesh", V, T, F)
+    U = igl.eigen.MatrixXd(V)
+    igl.readTGF(TUTORIAL_SHARED_PATH + "hand.tgf", C, BE)
+
+    # Retrieve parents for forward kinematics
+    igl.directed_edge_parents(BE, P)
+
+    # Read pose as matrix of quaternions per row
+    igl.readDMAT(TUTORIAL_SHARED_PATH + "hand-pose.dmat", Q)
+    igl.column_to_quats(Q, pose)
+    assert (len(pose) == BE.rows())
+
+    # List of boundary indices (aka fixed value indices into VV)
+    b = igl.eigen.MatrixXi()
+    # List of boundary conditions of each weight function
+    bc = igl.eigen.MatrixXd()
+
+    igl.boundary_conditions(V, T, C, igl.eigen.MatrixXi(), BE, igl.eigen.MatrixXi(), b, bc)
+
+    # compute BBW weights matrix
+    bbw_data = igl.bbw.BBWData()
+    # only a few iterations for sake of demo
+    bbw_data.active_set_params.max_iter = 8
+    bbw_data.verbosity = 2
+    if not igl.bbw.bbw(V, T, b, bc, bbw_data, W):
+        exit(-1)
+
+    # Normalize weights to sum to one
+    igl.normalize_row_sums(W, W)
+    # precompute linear blend skinning matrix
+    igl.lbs_matrix(V, W, M)
+
+    # Plot the mesh with pseudocolors
+    viewer = igl.viewer.Viewer()
+    viewer.data.set_mesh(U, F)
+    set_color(viewer)
+    viewer.data.set_edges(C, BE, sea_green)
+    viewer.core.show_lines = False
+    viewer.core.show_overlay_depth = False
+    viewer.core.line_width = 1
+    viewer.core.trackball_angle.normalize()
+    viewer.callback_pre_draw = pre_draw
+    viewer.callback_key_down = key_down
+    viewer.core.is_animating = False
+    viewer.core.animation_max_fps = 30.0
+    viewer.launch()

+ 140 - 0
python/tutorial/404_DualQuaternionSkinning.py

@@ -0,0 +1,140 @@
+import sys, os
+from math import sin, cos, pi
+
+# Add the igl library to the modules search path
+import math
+
+sys.path.insert(0, os.getcwd() + "/../")
+import pyigl as igl
+
+from shared import TUTORIAL_SHARED_PATH, check_dependencies, print_usage
+
+dependencies = ["viewer"]
+check_dependencies(dependencies)
+
+
+def pre_draw(viewer):
+    global recompute, anim_t, poses, C, BE, P, U, M, anim_t_dir
+
+    if recompute:
+        # Find pose interval
+        begin = int(math.floor(anim_t)) % len(poses)
+        end = int(math.floor(anim_t) + 1) % len(poses)
+        t = anim_t - math.floor(anim_t)
+
+        # Interpolate pose and identity
+        anim_pose = igl.RotationList()
+        for e in range(len(poses[begin])):
+            anim_pose.append(poses[begin][e].slerp(t, poses[end][e]))
+
+        # Propogate relative rotations via FK to retrieve absolute transformations
+        vQ = igl.RotationList()
+        vT = []
+        igl.forward_kinematics(C, BE, P, anim_pose, vQ, vT)
+        dim = C.cols()
+        T = igl.eigen.MatrixXd(BE.rows() * (dim + 1), dim)
+        for e in range(BE.rows()):
+            a = igl.eigen.Affine3d.Identity()
+            a.translate(vT[e])
+            a.rotate(vQ[e])
+            T.setBlock(e * (dim + 1), 0, dim + 1, dim, a.matrix().transpose().block(0, 0, dim + 1, dim))
+
+        # Compute deformation via LBS as matrix multiplication
+        if use_dqs:
+            igl.dqs(V, W, vQ, vT, U)
+        else:
+            U = M * T
+
+        # Also deform skeleton edges
+        CT = igl.eigen.MatrixXd()
+        BET = igl.eigen.MatrixXi()
+        igl.deform_skeleton(C, BE, T, CT, BET)
+
+        viewer.data.set_vertices(U)
+        viewer.data.set_edges(CT, BET, sea_green)
+        viewer.data.compute_normals()
+        if viewer.core.is_animating:
+            anim_t += anim_t_dir
+        else:
+            recompute = False
+
+    return False
+
+
+def key_down(viewer, key, mods):
+    global recompute, use_dqs, animation
+    recompute = True
+    if key == ord('D') or key == ord('d'):
+        use_dqs = not use_dqs
+        viewer.core.is_animating = False
+        animation = False
+        if use_dqs:
+            print("Switched to Dual Quaternion Skinning")
+        else:
+            print("Switched to Linear Blend Skinning")
+    elif key == ord(' '):
+        if animation:
+            viewer.core.is_animating = False
+            animation = False
+        else:
+            viewer.core.is_animating = True
+            animation = True
+    return False
+
+
+if __name__ == "__main__":
+    keys = {"d": "toggle between LBS and DQS",
+            "space": "toggle animation"}
+
+    print_usage(keys)
+
+    V = igl.eigen.MatrixXd()
+    F = igl.eigen.MatrixXi()
+    C = igl.eigen.MatrixXd()
+    BE = igl.eigen.MatrixXi()
+    P = igl.eigen.MatrixXi()
+    W = igl.eigen.MatrixXd()
+    M = igl.eigen.MatrixXd()
+
+    sea_green = igl.eigen.MatrixXd([[70. / 255., 252. / 255., 167. / 255.]])
+
+    anim_t = 0.0
+    anim_t_dir = 0.015
+    use_dqs = False
+    recompute = True
+    animation = False  # Flag needed as there is some synchronization problem with viewer.core.is_animating
+
+    poses = [[]]
+
+    igl.readOBJ(TUTORIAL_SHARED_PATH + "arm.obj", V, F)
+    U = igl.eigen.MatrixXd(V)
+    igl.readTGF(TUTORIAL_SHARED_PATH + "arm.tgf", C, BE)
+
+    # retrieve parents for forward kinematics
+    igl.directed_edge_parents(BE, P)
+    rest_pose = igl.RotationList()
+    igl.directed_edge_orientations(C, BE, rest_pose)
+    poses = [[igl.eigen.Quaterniond.Identity() for i in range(4)] for j in range(4)]
+
+    twist = igl.eigen.Quaterniond(pi, igl.eigen.MatrixXd([1, 0, 0]))
+    poses[1][2] = rest_pose[2] * twist * rest_pose[2].conjugate()
+    bend = igl.eigen.Quaterniond(-pi * 0.7, igl.eigen.MatrixXd([0, 0, 1]))
+    poses[3][2] = rest_pose[2] * bend * rest_pose[2].conjugate()
+
+    igl.readDMAT(TUTORIAL_SHARED_PATH + "arm-weights.dmat", W)
+    igl.lbs_matrix(V, W, M)
+
+    # Plot the mesh with pseudocolors
+    viewer = igl.viewer.Viewer()
+    viewer.data.set_mesh(U, F)
+    viewer.data.set_edges(C, BE, sea_green)
+    viewer.core.show_lines = False
+    viewer.core.show_overlay_depth = False
+    viewer.core.line_width = 1
+    viewer.core.trackball_angle.normalize()
+    viewer.callback_pre_draw = pre_draw
+    viewer.callback_key_down = key_down
+    viewer.core.is_animating = False
+    viewer.core.camera_zoom = 2.5
+    viewer.core.animation_max_fps = 30.0
+    viewer.launch()

+ 2 - 1
shared/cmake/CMakeLists.txt

@@ -372,6 +372,7 @@ endif()
 
 ### Compile the viewer ###
 if(LIBIGL_WITH_VIEWER)
+  find_package(OpenGL REQUIRED)
   set(NANOGUI_DIR "${LIBIGL_EXTERNAL}/nanogui")
 
   if(LIBIGL_WITH_NANOGUI)
@@ -400,7 +401,7 @@ if(LIBIGL_WITH_VIEWER)
     add_subdirectory("${NANOGUI_DIR}/ext/glfw" "glfw")
 
     set(VIEWER_INCLUDE_DIRS "${NANOGUI_DIR}/ext/glfw/include")
-    set(LIBIGL_VIEWER_EXTRA_LIBRARIES "glfw" ${GLFW_LIBRARIES})
+    set(LIBIGL_VIEWER_EXTRA_LIBRARIES "glfw" ${OPENGL_gl_LIBRARY})
   endif()
 
   ### GLEW for linux and windows

+ 1 - 1
tutorial/tutorial.html.REMOVED.git-id

@@ -1 +1 @@
-02cf5efb916ce8e885dcaeee5a89f91fa4e1f440
+cd11b42bda4357cfaae8f62d5036f840df5b627d

+ 1 - 1
tutorial/tutorial.md.REMOVED.git-id

@@ -1 +1 @@
-521b2da65bd08996d25fb1fab30ff66f704da312
+91d360c45d833747534b3dd524f5d2b39a1e73b4