Browse Source

expose unproject_in_mesh to main library with default brute force option

Former-commit-id: 9834731b6b2963355c8041ad8cc722b0dc56fcb0
Alec Jacobson 9 years ago
parent
commit
a1e8235f15

+ 25 - 0
include/igl/Hit.h

@@ -0,0 +1,25 @@
+// This file is part of libigl, a simple c++ geometry processing library.
+// 
+// Copyright (C) 2015 Alec Jacobson <alecjacobson@gmail.com>
+//               2014 Christian Schüller <schuellchr@gmail.com> 
+//
+// 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_HIT_H
+#define IGL_HIT_H
+
+namespace igl
+{
+  // Reimplementation of the embree::Hit struct from embree1.0
+  // 
+  // TODO: template on floating point type
+  struct Hit
+  {
+    int id; // primitive id
+    int gid; // geometry id
+    float u,v; // barycentric coordinates
+    float t; // distance = direction*t to intersection
+  };
+}
+#endif 

+ 1 - 1
include/igl/embree/EmbreeIntersector.h

@@ -16,7 +16,7 @@
 #ifndef IGL_EMBREE_EMBREE_INTERSECTOR_H
 #define IGL_EMBREE_EMBREE_INTERSECTOR_H
 
-#include "Hit.h"
+#include "../Hit.h"
 #include <Eigen/Geometry>
 #include <Eigen/Core>
 #include <Eigen/Geometry>

+ 0 - 26
include/igl/embree/Hit.h

@@ -1,26 +0,0 @@
-// This file is part of libigl, a simple c++ geometry processing library.
-// 
-// Copyright (C) 2013 Alec Jacobson <alecjacobson@gmail.com>
-//               2014 Christian Schüller <schuellchr@gmail.com> 
-//
-// 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_HIT_H
-#define IGL_EMBREE_HIT_H
-
-namespace igl
-{
-  namespace embree
-  {
-    // Reimplementation of the embree::Hit struct from embree1.0
-    struct Hit
-    {
-      int id; // primitive id
-      int gid; // geometry id
-      float u,v; // barycentric coordinates
-      float t; // distance = direction*t to intersection
-    };
-  }
-}
-#endif 

+ 4 - 3
include/igl/embree/ambient_occlusion.cpp

@@ -7,8 +7,9 @@
 // obtain one at http://mozilla.org/MPL/2.0/.
 #include "ambient_occlusion.h"
 #include "EmbreeIntersector.h"
-#include <igl/random_dir.h>
-#include <igl/EPS.h>
+#include "../Hit.h"
+#include "../random_dir.h"
+#include "../EPS.h"
 
 template <
   typename DerivedP,
@@ -44,7 +45,7 @@ IGL_INLINE void igl::embree::ambient_occlusion(
         // reverse ray
         d *= -1;
       }
-      igl::embree::Hit hit;
+      igl::Hit hit;
       const float tnear = 1e-4f;
       if(ei.intersectRay(origin,d,hit,tnear))
       {

+ 5 - 4
include/igl/embree/bone_visible.cpp

@@ -6,9 +6,10 @@
 // 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/.
 #include "bone_visible.h"
-#include <igl/project_to_line.h>
-#include <igl/EPS.h>
-#include <igl/Timer.h>
+#include "../project_to_line.h"
+#include "../EPS.h"
+#include "../Hit.h"
+#include "../Timer.h"
 #include <iostream>
 
 template <
@@ -86,7 +87,7 @@ IGL_INLINE void igl::embree::bone_visible(
         projv = d;
       }
     }
-    igl::embree::Hit hit;
+    igl::Hit hit;
     // perhaps 1.0 should be 1.0-epsilon, or actually since we checking the
     // incident face, perhaps 1.0 should be 1.0+eps
     const Vector3d dir = (Vv-projv)*1.0;

+ 2 - 1
include/igl/embree/line_mesh_intersection.cpp

@@ -6,6 +6,7 @@
 // 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/.
 #include "line_mesh_intersection.h"
+#include "../Hit.h"
 
 // For error printing
 #include <cstdio>
@@ -40,7 +41,7 @@ IGL_INLINE ScalarMatrix igl::embree::line_mesh_intersection
   // Shoot rays from the source to the target
   for (unsigned i=0; i<ray_pos.rows(); ++i)
   {
-    igl::embree::Hit A,B;
+    igl::Hit A,B;
     // Shoot ray A
     Eigen::RowVector3d A_pos = ray_pos.row(i) + tol * ray_dir.row(i);
     Eigen::RowVector3d A_dir = -ray_dir.row(i);

+ 14 - 34
include/igl/embree/unproject_in_mesh.cpp

@@ -7,7 +7,8 @@
 // obtain one at http://mozilla.org/MPL/2.0/.
 #include "unproject_in_mesh.h"
 #include "EmbreeIntersector.h"
-#include "../unproject.h"
+#include "../unproject_ray.h"
+#include "../unproject_in_mesh.h"
 #include <vector>
 
 template <typename Derivedobj>
@@ -18,41 +19,20 @@ IGL_INLINE int igl::embree::unproject_in_mesh(
   const Eigen::Vector4f& viewport,
   const EmbreeIntersector & ei,
   Eigen::PlainObjectBase<Derivedobj> & obj,
-  std::vector<igl::embree::Hit > & hits)
+  std::vector<igl::Hit > & hits)
 {
   using namespace igl;
   using namespace std;
   using namespace Eigen;
-  // Source and direction on screen
-  Vector3f win_s(pos(0),pos(1),0);
-  Vector3f win_d(pos(0),pos(1),1);
-  // Source, destination and direction in world
-  Vector3f s,d,dir;
-  s = igl::unproject(win_s,model,proj,viewport);
-  d = igl::unproject(win_d,model,proj,viewport);
-  dir = d-s;
-
-  // Shoot ray, collect all hits (could just collect first two)
-  int num_rays_shot;
-  hits.clear();
-  ei.intersectRay(s,dir,hits,num_rays_shot);
-  switch(hits.size())
+  const auto & shoot_ray = [&ei](
+    const Eigen::Vector3f& s,
+    const Eigen::Vector3f& dir,
+    std::vector<igl::Hit> & hits)
   {
-    case 0:
-      break;
-    case 1:
-    {
-      obj = (s + dir*hits[0].t).cast<typename Derivedobj::Scalar>();
-      break;
-    }
-    case 2:
-    default:
-    {
-      obj = 0.5*((s + dir*hits[0].t) + (s + dir*hits[1].t)).cast<typename Derivedobj::Scalar>();
-      break;
-    }
-  }
-  return hits.size();
+    int num_rays_shot;
+    ei.intersectRay(s,dir,hits,num_rays_shot);
+  };
+  return igl::unproject_in_mesh(pos,model,proj,viewport,shoot_ray,obj,hits);
 }
 
 template <typename Derivedobj>
@@ -64,13 +44,13 @@ IGL_INLINE int igl::embree::unproject_in_mesh(
     const EmbreeIntersector & ei,
     Eigen::PlainObjectBase<Derivedobj> & obj)
 {
-  std::vector<igl::embree::Hit> hits;
+  std::vector<igl::Hit> hits;
   return unproject_in_mesh(pos,model,proj,viewport,ei,obj,hits);
 }
 
 
 #ifdef IGL_STATIC_LIBRARY
-template int igl::embree::unproject_in_mesh<Eigen::Matrix<double, -1, -1, 0, -1, -1> >(Eigen::Matrix<float, 2, 1, 0, 2, 1> const&, Eigen::Matrix<float, 4, 4, 0, 4, 4> const&, Eigen::Matrix<float, 4, 4, 0, 4, 4> const&, Eigen::Matrix<float, 4, 1, 0, 4, 1> const&, igl::embree::EmbreeIntersector const&, Eigen::PlainObjectBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> >&, std::vector<igl::embree::Hit, std::allocator<igl::embree::Hit> >&);
-template int igl::embree::unproject_in_mesh<Eigen::Matrix<double, 1, 3, 1, 1, 3> >(Eigen::Matrix<float, 2, 1, 0, 2, 1> const&, Eigen::Matrix<float, 4, 4, 0, 4, 4> const&, Eigen::Matrix<float, 4, 4, 0, 4, 4> const&, Eigen::Matrix<float, 4, 1, 0, 4, 1> const&, igl::embree::EmbreeIntersector const&, Eigen::PlainObjectBase<Eigen::Matrix<double, 1, 3, 1, 1, 3> >&, std::vector<igl::embree::Hit, std::allocator<igl::embree::Hit> >&);
+template int igl::embree::unproject_in_mesh<Eigen::Matrix<double, -1, -1, 0, -1, -1> >(Eigen::Matrix<float, 2, 1, 0, 2, 1> const&, Eigen::Matrix<float, 4, 4, 0, 4, 4> const&, Eigen::Matrix<float, 4, 4, 0, 4, 4> const&, Eigen::Matrix<float, 4, 1, 0, 4, 1> const&, igl::embree::EmbreeIntersector const&, Eigen::PlainObjectBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> >&, std::vector<igl::Hit, std::allocator<igl::Hit> >&);
+template int igl::embree::unproject_in_mesh<Eigen::Matrix<double, 1, 3, 1, 1, 3> >(Eigen::Matrix<float, 2, 1, 0, 2, 1> const&, Eigen::Matrix<float, 4, 4, 0, 4, 4> const&, Eigen::Matrix<float, 4, 4, 0, 4, 4> const&, Eigen::Matrix<float, 4, 1, 0, 4, 1> const&, igl::embree::EmbreeIntersector const&, Eigen::PlainObjectBase<Eigen::Matrix<double, 1, 3, 1, 1, 3> >&, std::vector<igl::Hit, std::allocator<igl::Hit> >&);
 template int igl::embree::unproject_in_mesh<Eigen::Matrix<double, 3, 1, 0, 3, 1> >(Eigen::Matrix<float, 2, 1, 0, 2, 1> const&, Eigen::Matrix<float, 4, 4, 0, 4, 4> const&, Eigen::Matrix<float, 4, 4, 0, 4, 4> const&, Eigen::Matrix<float, 4, 1, 0, 4, 1> const&, igl::embree::EmbreeIntersector const&, Eigen::PlainObjectBase<Eigen::Matrix<double, 3, 1, 0, 3, 1> >&);
 #endif

+ 2 - 2
include/igl/embree/unproject_in_mesh.h

@@ -11,7 +11,7 @@
 #include <Eigen/Core>
 
 #include <vector>
-#include "Hit.h"
+#include "../Hit.h"
 
 namespace igl
 {
@@ -54,7 +54,7 @@ namespace igl
       const Eigen::Vector4f& viewport,
       const EmbreeIntersector & ei,
       Eigen::PlainObjectBase<Derivedobj> & obj,
-      std::vector<igl::embree::Hit > & hits);
+      std::vector<igl::Hit > & hits);
     template < typename Derivedobj>
     IGL_INLINE int unproject_in_mesh(
       const Eigen::Vector2f& pos,

+ 1 - 1
include/igl/embree/unproject_onto_mesh.cpp

@@ -24,7 +24,7 @@ IGL_INLINE bool igl::embree::unproject_onto_mesh(
   using namespace std;
   using namespace Eigen;
   MatrixXd obj;
-  vector<igl::embree::Hit> hits;
+  vector<igl::Hit> hits;
 
   // This is lazy, it will find more than just the first hit
   unproject_in_mesh(pos,model,proj,viewport,ei,obj,hits);

+ 0 - 1
include/igl/embree/unproject_onto_mesh.h

@@ -11,7 +11,6 @@
 #include <Eigen/Core>
 
 #include <vector>
-#include "Hit.h"
 
 namespace igl
 {

+ 264 - 0
include/igl/raytri.c

@@ -0,0 +1,264 @@
+/* Ray-Triangle Intersection Test Routines          */
+/* Different optimizations of my and Ben Trumbore's */
+/* code from journals of graphics tools (JGT)       */
+/* http://www.acm.org/jgt/                          */
+/* by Tomas Moller, May 2000                        */
+
+
+// Alec: I've added an include guard, made all functions inline and added
+// IGL_RAY_TRI_ to #define macros
+#ifndef IGL_RAY_TRI_C
+#define IGL_RAY_TRI_C
+
+#include <math.h>
+
+#define IGL_RAY_TRI_EPSILON 0.000001
+#define IGL_RAY_TRI_CROSS(dest,v1,v2) \
+          dest[0]=v1[1]*v2[2]-v1[2]*v2[1]; \
+          dest[1]=v1[2]*v2[0]-v1[0]*v2[2]; \
+          dest[2]=v1[0]*v2[1]-v1[1]*v2[0];
+#define IGL_RAY_TRI_DOT(v1,v2) (v1[0]*v2[0]+v1[1]*v2[1]+v1[2]*v2[2])
+#define IGL_RAY_TRI_SUB(dest,v1,v2) \
+          dest[0]=v1[0]-v2[0]; \
+          dest[1]=v1[1]-v2[1]; \
+          dest[2]=v1[2]-v2[2]; 
+
+/* the original jgt code */
+inline int intersect_triangle(double orig[3], double dir[3],
+		       double vert0[3], double vert1[3], double vert2[3],
+		       double *t, double *u, double *v)
+{
+   double edge1[3], edge2[3], tvec[3], pvec[3], qvec[3];
+   double det,inv_det;
+
+   /* find vectors for two edges sharing vert0 */
+   IGL_RAY_TRI_SUB(edge1, vert1, vert0);
+   IGL_RAY_TRI_SUB(edge2, vert2, vert0);
+
+   /* begin calculating determinant - also used to calculate U parameter */
+   IGL_RAY_TRI_CROSS(pvec, dir, edge2);
+
+   /* if determinant is near zero, ray lies in plane of triangle */
+   det = IGL_RAY_TRI_DOT(edge1, pvec);
+
+   if (det > -IGL_RAY_TRI_EPSILON && det < IGL_RAY_TRI_EPSILON)
+     return 0;
+   inv_det = 1.0 / det;
+
+   /* calculate distance from vert0 to ray origin */
+   IGL_RAY_TRI_SUB(tvec, orig, vert0);
+
+   /* calculate U parameter and test bounds */
+   *u = IGL_RAY_TRI_DOT(tvec, pvec) * inv_det;
+   if (*u < 0.0 || *u > 1.0)
+     return 0;
+
+   /* prepare to test V parameter */
+   IGL_RAY_TRI_CROSS(qvec, tvec, edge1);
+
+   /* calculate V parameter and test bounds */
+   *v = IGL_RAY_TRI_DOT(dir, qvec) * inv_det;
+   if (*v < 0.0 || *u + *v > 1.0)
+     return 0;
+
+   /* calculate t, ray intersects triangle */
+   *t = IGL_RAY_TRI_DOT(edge2, qvec) * inv_det;
+
+   return 1;
+}
+
+
+/* code rewritten to do tests on the sign of the determinant */
+/* the division is at the end in the code                    */
+inline int intersect_triangle1(double orig[3], double dir[3],
+			double vert0[3], double vert1[3], double vert2[3],
+			double *t, double *u, double *v)
+{
+   double edge1[3], edge2[3], tvec[3], pvec[3], qvec[3];
+   double det,inv_det;
+
+   /* find vectors for two edges sharing vert0 */
+   IGL_RAY_TRI_SUB(edge1, vert1, vert0);
+   IGL_RAY_TRI_SUB(edge2, vert2, vert0);
+
+   /* begin calculating determinant - also used to calculate U parameter */
+   IGL_RAY_TRI_CROSS(pvec, dir, edge2);
+
+   /* if determinant is near zero, ray lies in plane of triangle */
+   det = IGL_RAY_TRI_DOT(edge1, pvec);
+
+   if (det > IGL_RAY_TRI_EPSILON)
+   {
+      /* calculate distance from vert0 to ray origin */
+      IGL_RAY_TRI_SUB(tvec, orig, vert0);
+      
+      /* calculate U parameter and test bounds */
+      *u = IGL_RAY_TRI_DOT(tvec, pvec);
+      if (*u < 0.0 || *u > det)
+	 return 0;
+      
+      /* prepare to test V parameter */
+      IGL_RAY_TRI_CROSS(qvec, tvec, edge1);
+      
+      /* calculate V parameter and test bounds */
+      *v = IGL_RAY_TRI_DOT(dir, qvec);
+      if (*v < 0.0 || *u + *v > det)
+	 return 0;
+      
+   }
+   else if(det < -IGL_RAY_TRI_EPSILON)
+   {
+      /* calculate distance from vert0 to ray origin */
+      IGL_RAY_TRI_SUB(tvec, orig, vert0);
+      
+      /* calculate U parameter and test bounds */
+      *u = IGL_RAY_TRI_DOT(tvec, pvec);
+/*      printf("*u=%f\n",(float)*u); */
+/*      printf("det=%f\n",det); */
+      if (*u > 0.0 || *u < det)
+	 return 0;
+      
+      /* prepare to test V parameter */
+      IGL_RAY_TRI_CROSS(qvec, tvec, edge1);
+      
+      /* calculate V parameter and test bounds */
+      *v = IGL_RAY_TRI_DOT(dir, qvec) ;
+      if (*v > 0.0 || *u + *v < det)
+	 return 0;
+   }
+   else return 0;  /* ray is parallell to the plane of the triangle */
+
+
+   inv_det = 1.0 / det;
+
+   /* calculate t, ray intersects triangle */
+   *t = IGL_RAY_TRI_DOT(edge2, qvec) * inv_det;
+   (*u) *= inv_det;
+   (*v) *= inv_det;
+
+   return 1;
+}
+
+/* code rewritten to do tests on the sign of the determinant */
+/* the division is before the test of the sign of the det    */
+inline int intersect_triangle2(double orig[3], double dir[3],
+			double vert0[3], double vert1[3], double vert2[3],
+			double *t, double *u, double *v)
+{
+   double edge1[3], edge2[3], tvec[3], pvec[3], qvec[3];
+   double det,inv_det;
+
+   /* find vectors for two edges sharing vert0 */
+   IGL_RAY_TRI_SUB(edge1, vert1, vert0);
+   IGL_RAY_TRI_SUB(edge2, vert2, vert0);
+
+   /* begin calculating determinant - also used to calculate U parameter */
+   IGL_RAY_TRI_CROSS(pvec, dir, edge2);
+
+   /* if determinant is near zero, ray lies in plane of triangle */
+   det = IGL_RAY_TRI_DOT(edge1, pvec);
+
+   /* calculate distance from vert0 to ray origin */
+   IGL_RAY_TRI_SUB(tvec, orig, vert0);
+   inv_det = 1.0 / det;
+   
+   if (det > IGL_RAY_TRI_EPSILON)
+   {
+      /* calculate U parameter and test bounds */
+      *u = IGL_RAY_TRI_DOT(tvec, pvec);
+      if (*u < 0.0 || *u > det)
+	 return 0;
+      
+      /* prepare to test V parameter */
+      IGL_RAY_TRI_CROSS(qvec, tvec, edge1);
+      
+      /* calculate V parameter and test bounds */
+      *v = IGL_RAY_TRI_DOT(dir, qvec);
+      if (*v < 0.0 || *u + *v > det)
+	 return 0;
+      
+   }
+   else if(det < -IGL_RAY_TRI_EPSILON)
+   {
+      /* calculate U parameter and test bounds */
+      *u = IGL_RAY_TRI_DOT(tvec, pvec);
+      if (*u > 0.0 || *u < det)
+	 return 0;
+      
+      /* prepare to test V parameter */
+      IGL_RAY_TRI_CROSS(qvec, tvec, edge1);
+      
+      /* calculate V parameter and test bounds */
+      *v = IGL_RAY_TRI_DOT(dir, qvec) ;
+      if (*v > 0.0 || *u + *v < det)
+	 return 0;
+   }
+   else return 0;  /* ray is parallell to the plane of the triangle */
+
+   /* calculate t, ray intersects triangle */
+   *t = IGL_RAY_TRI_DOT(edge2, qvec) * inv_det;
+   (*u) *= inv_det;
+   (*v) *= inv_det;
+
+   return 1;
+}
+
+/* code rewritten to do tests on the sign of the determinant */
+/* the division is before the test of the sign of the det    */
+/* and one IGL_RAY_TRI_CROSS has been moved out from the if-else if-else */
+inline int intersect_triangle3(double orig[3], double dir[3],
+			double vert0[3], double vert1[3], double vert2[3],
+			double *t, double *u, double *v)
+{
+   double edge1[3], edge2[3], tvec[3], pvec[3], qvec[3];
+   double det,inv_det;
+
+   /* find vectors for two edges sharing vert0 */
+   IGL_RAY_TRI_SUB(edge1, vert1, vert0);
+   IGL_RAY_TRI_SUB(edge2, vert2, vert0);
+
+   /* begin calculating determinant - also used to calculate U parameter */
+   IGL_RAY_TRI_CROSS(pvec, dir, edge2);
+
+   /* if determinant is near zero, ray lies in plane of triangle */
+   det = IGL_RAY_TRI_DOT(edge1, pvec);
+
+   /* calculate distance from vert0 to ray origin */
+   IGL_RAY_TRI_SUB(tvec, orig, vert0);
+   inv_det = 1.0 / det;
+   
+   IGL_RAY_TRI_CROSS(qvec, tvec, edge1);
+      
+   if (det > IGL_RAY_TRI_EPSILON)
+   {
+      *u = IGL_RAY_TRI_DOT(tvec, pvec);
+      if (*u < 0.0 || *u > det)
+	 return 0;
+            
+      /* calculate V parameter and test bounds */
+      *v = IGL_RAY_TRI_DOT(dir, qvec);
+      if (*v < 0.0 || *u + *v > det)
+	 return 0;
+      
+   }
+   else if(det < -IGL_RAY_TRI_EPSILON)
+   {
+      /* calculate U parameter and test bounds */
+      *u = IGL_RAY_TRI_DOT(tvec, pvec);
+      if (*u > 0.0 || *u < det)
+	 return 0;
+      
+      /* calculate V parameter and test bounds */
+      *v = IGL_RAY_TRI_DOT(dir, qvec) ;
+      if (*v > 0.0 || *u + *v < det)
+	 return 0;
+   }
+   else return 0;  /* ray is parallell to the plane of the triangle */
+
+   *t = IGL_RAY_TRI_DOT(edge2, qvec) * inv_det;
+   (*u) *= inv_det;
+   (*v) *= inv_det;
+
+   return 1;
+}
+#endif

+ 28 - 8
include/igl/unproject.cpp

@@ -10,14 +10,22 @@
 #include <Eigen/Dense>
 #include <Eigen/LU>
 
-template <typename Scalar>
-IGL_INLINE Eigen::Matrix<Scalar,3,1> igl::unproject(
-  const    Eigen::Matrix<Scalar,3,1>&  win,
-  const    Eigen::Matrix<Scalar,4,4>& model,
-  const    Eigen::Matrix<Scalar,4,4>& proj,
-  const    Eigen::Matrix<Scalar,4,1>&  viewport)
+template <
+  typename Derivedwin,
+  typename Derivedmodel,
+  typename Derivedproj,
+  typename Derivedviewport,
+  typename Derivedscene>
+IGL_INLINE void igl::unproject(
+  const Eigen::PlainObjectBase<Derivedwin>&  win,
+  const Eigen::PlainObjectBase<Derivedmodel>& model,
+  const Eigen::PlainObjectBase<Derivedproj>& proj,
+  const Eigen::PlainObjectBase<Derivedviewport>&  viewport,
+  Eigen::PlainObjectBase<Derivedscene> & scene)
 {
-  Eigen::Matrix<Scalar,4,4> Inverse = (proj * model).inverse();
+  typedef typename Derivedscene::Scalar Scalar;
+  Eigen::Matrix<Scalar,4,4> Inverse = 
+    (proj.template cast<Scalar>() * model.template cast<Scalar>()).inverse();
 
   Eigen::Matrix<Scalar,4,1> tmp;
   tmp << win, 1;
@@ -28,7 +36,19 @@ IGL_INLINE Eigen::Matrix<Scalar,3,1> igl::unproject(
   Eigen::Matrix<Scalar,4,1> obj = Inverse * tmp;
   obj /= obj(3);
 
-  return obj.head(3);
+  scene = obj.head(3);
+}
+
+template <typename Scalar>
+IGL_INLINE Eigen::Matrix<Scalar,3,1> igl::unproject(
+  const    Eigen::Matrix<Scalar,3,1>&  win,
+  const    Eigen::Matrix<Scalar,4,4>& model,
+  const    Eigen::Matrix<Scalar,4,4>& proj,
+  const    Eigen::Matrix<Scalar,4,1>&  viewport)
+{
+  Eigen::Matrix<Scalar,3,1> scene;
+  unproject(win,model,proj,viewport,scene);
+  return scene;
 }
 
 #ifdef IGL_STATIC_LIBRARY

+ 22 - 7
include/igl/unproject.h

@@ -12,17 +12,32 @@
 namespace igl
 {
   // Eigen reimplementation of gluUnproject
+  //
   // Inputs:
   //   win  screen space x, y, and z coordinates
-  // Returns:
-  //   the unprojected x, y, and z coordinates
-  // Returns return value of gluUnProject call
+  //   model  4x4 model-view matrix
+  //   proj  4x4 projection matrix
+  //   viewport  4-long viewport vector
+  // Outputs:
+  //   scene  the unprojected x, y, and z coordinates
+  template <
+    typename Derivedwin,
+    typename Derivedmodel,
+    typename Derivedproj,
+    typename Derivedviewport,
+    typename Derivedscene>
+  IGL_INLINE void unproject(
+    const Eigen::PlainObjectBase<Derivedwin>&  win,
+    const Eigen::PlainObjectBase<Derivedmodel>& model,
+    const Eigen::PlainObjectBase<Derivedproj>& proj,
+    const Eigen::PlainObjectBase<Derivedviewport>&  viewport,
+    Eigen::PlainObjectBase<Derivedscene> & scene);
   template <typename Scalar>
   IGL_INLINE Eigen::Matrix<Scalar,3,1> unproject(
-    const    Eigen::Matrix<Scalar,3,1>&  win,
-    const    Eigen::Matrix<Scalar,4,4>& model,
-    const    Eigen::Matrix<Scalar,4,4>& proj,
-    const    Eigen::Matrix<Scalar,4,1>&  viewport);
+    const Eigen::Matrix<Scalar,3,1>&  win,
+    const Eigen::Matrix<Scalar,4,4>& model,
+    const Eigen::Matrix<Scalar,4,4>& proj,
+    const Eigen::Matrix<Scalar,4,1>&  viewport);
 }
 
 

+ 117 - 0
include/igl/unproject_in_mesh.cpp

@@ -0,0 +1,117 @@
+// This file is part of libigl, a simple c++ geometry processing library.
+//
+// Copyright (C) 2015 Alec Jacobson <alecjacobson@gmail.com>
+//
+// 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/.
+#include "unproject_in_mesh.h"
+#include "unproject_ray.h"
+
+template < typename Derivedobj>
+  IGL_INLINE int igl::unproject_in_mesh(
+      const Eigen::Vector2f& pos,
+      const Eigen::Matrix4f& model,
+      const Eigen::Matrix4f& proj,
+      const Eigen::Vector4f& viewport,
+      const std::function<
+        void(
+          const Eigen::Vector3f&,
+          const Eigen::Vector3f&,
+          std::vector<igl::Hit> &)
+          > & shoot_ray,
+      Eigen::PlainObjectBase<Derivedobj> & obj,
+      std::vector<igl::Hit > & hits)
+{
+  using namespace igl;
+  using namespace std;
+  using namespace Eigen;
+  Vector3f s,dir;
+  unproject_ray(pos,model,proj,viewport,s,dir);
+  shoot_ray(s,dir,hits);
+  switch(hits.size())
+  {
+    case 0:
+      break;
+    case 1:
+    {
+      obj = (s + dir*hits[0].t).cast<typename Derivedobj::Scalar>();
+      break;
+    }
+    case 2:
+    default:
+    {
+      obj = 0.5*((s + dir*hits[0].t) + (s + dir*hits[1].t)).cast<typename Derivedobj::Scalar>();
+      break;
+    }
+  }
+  return hits.size();
+}
+
+extern "C"
+{
+#include "raytri.c"
+}
+
+template < typename DerivedV, typename DerivedF, typename Derivedobj>
+  IGL_INLINE int igl::unproject_in_mesh(
+      const Eigen::Vector2f& pos,
+      const Eigen::Matrix4f& model,
+      const Eigen::Matrix4f& proj,
+      const Eigen::Vector4f& viewport,
+      const Eigen::PlainObjectBase<DerivedV> & V,
+      const Eigen::PlainObjectBase<DerivedF> & F,
+      Eigen::PlainObjectBase<Derivedobj> & obj,
+      std::vector<igl::Hit > & hits)
+{
+  using namespace igl;
+  using namespace std;
+  using namespace Eigen;
+  const auto & shoot_ray = [&V,&F](
+    const Eigen::Vector3f& s,
+    const Eigen::Vector3f& dir,
+    std::vector<igl::Hit> & hits)
+  {
+    // Should be but can't be const 
+    Vector3d s_d = s.template cast<double>();
+    Vector3d dir_d = dir.template cast<double>();
+    hits.clear();
+    // loop over all triangles
+    for(int f = 0;f<F.rows();f++)
+    {
+      // Should be but can't be const 
+      RowVector3d v0 = V.row(F(f,0)).template cast<double>();
+      RowVector3d v1 = V.row(F(f,1)).template cast<double>();
+      RowVector3d v2 = V.row(F(f,2)).template cast<double>();
+      // shoot ray, record hit
+      double t,u,v;
+      if(intersect_triangle1(
+        s_d.data(), dir_d.data(), v0.data(), v1.data(), v2.data(), &t, &u, &v))
+      {
+        hits.push_back({(int)f,(int)-1,(float)u,(float)v,(float)t});
+      }
+    }
+    // Sort hits based on distance
+    std::sort(
+      hits.begin(),
+      hits.end(),
+      [](const Hit & a, const Hit & b)->bool{ return a.t < b.t;});
+  };
+  return unproject_in_mesh(pos,model,proj,viewport,shoot_ray,obj,hits);
+}
+
+template < typename DerivedV, typename DerivedF, typename Derivedobj>
+  IGL_INLINE int igl::unproject_in_mesh(
+      const Eigen::Vector2f& pos,
+      const Eigen::Matrix4f& model,
+      const Eigen::Matrix4f& proj,
+      const Eigen::Vector4f& viewport,
+      const Eigen::PlainObjectBase<DerivedV> & V,
+      const Eigen::PlainObjectBase<DerivedF> & F,
+      Eigen::PlainObjectBase<Derivedobj> & obj)
+{
+  std::vector<igl::Hit> hits;
+  return unproject_in_mesh(pos,model,proj,viewport,V,F,obj,hits);
+}
+#ifdef IGL_STATIC_LIBRARY
+#endif

+ 87 - 0
include/igl/unproject_in_mesh.h

@@ -0,0 +1,87 @@
+// This file is part of libigl, a simple c++ geometry processing library.
+//
+// Copyright (C) 2015 Alec Jacobson <alecjacobson@gmail.com>
+//
+// 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_UNPROJECT_IN_MESH
+#define IGL_UNPROJECT_IN_MESH
+#include "igl_inline.h"
+#include <Eigen/Core>
+
+#include <vector>
+#include "Hit.h"
+
+namespace igl
+{
+  // Unproject a screen location (using current opengl viewport, projection, and
+  // model view) to a 3D position _inside_ a given mesh. If the ray through the
+  // given screen location (x,y) _hits_ the mesh more than twice then the 3D
+  // midpoint between the first two hits is return. If it hits once, then that
+  // point is return. If it does not hit the mesh then obj is not set.
+  //
+  // Inputs:
+  //    pos        screen space coordinates
+  //    model      model matrix
+  //    proj       projection matrix
+  //    viewport   vieweport vector
+  //    V   #V by 3 list of mesh vertex positions
+  //    F   #F by 3 list of mesh triangle indices into V
+  // Outputs:
+  //    obj        3d unprojected mouse point in mesh
+  //    hits       vector of hits
+  // Returns number of hits
+  //
+  template < typename DerivedV, typename DerivedF, typename Derivedobj>
+    IGL_INLINE int unproject_in_mesh(
+        const Eigen::Vector2f& pos,
+        const Eigen::Matrix4f& model,
+        const Eigen::Matrix4f& proj,
+        const Eigen::Vector4f& viewport,
+        const Eigen::PlainObjectBase<DerivedV> & V,
+        const Eigen::PlainObjectBase<DerivedF> & F,
+        Eigen::PlainObjectBase<Derivedobj> & obj,
+        std::vector<igl::Hit > & hits);
+  //
+  // Inputs:
+  //    pos        screen space coordinates
+  //    model      model matrix
+  //    proj       projection matrix
+  //    viewport   vieweport vector
+  //    shoot_ray  function handle that outputs hits of a given ray against a
+  //      mesh (embedded in function handles as captured variable/data)
+  // Outputs:
+  //    obj        3d unprojected mouse point in mesh
+  //    hits       vector of hits
+  // Returns number of hits
+  //
+  template < typename Derivedobj>
+    IGL_INLINE int unproject_in_mesh(
+        const Eigen::Vector2f& pos,
+        const Eigen::Matrix4f& model,
+        const Eigen::Matrix4f& proj,
+        const Eigen::Vector4f& viewport,
+        const std::function<
+          void(
+            const Eigen::Vector3f&,
+            const Eigen::Vector3f&,
+            std::vector<igl::Hit> &)
+            > & shoot_ray,
+        Eigen::PlainObjectBase<Derivedobj> & obj,
+        std::vector<igl::Hit > & hits);
+  template < typename DerivedV, typename DerivedF, typename Derivedobj>
+    IGL_INLINE int unproject_in_mesh(
+        const Eigen::Vector2f& pos,
+        const Eigen::Matrix4f& model,
+        const Eigen::Matrix4f& proj,
+        const Eigen::Vector4f& viewport,
+        const Eigen::PlainObjectBase<DerivedV> & V,
+        const Eigen::PlainObjectBase<DerivedF> & F,
+        Eigen::PlainObjectBase<Derivedobj> & obj);
+}
+#ifndef IGL_STATIC_LIBRARY
+#  include "unproject_in_mesh.cpp"
+#endif
+#endif
+

+ 38 - 0
include/igl/unproject_ray.cpp

@@ -0,0 +1,38 @@
+// This file is part of libigl, a simple c++ geometry processing library.
+//
+// Copyright (C) 2015 Alec Jacobson <alecjacobson@gmail.com>
+//
+// 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/.
+#include "unproject_ray.h"
+#include "unproject.h"
+
+template <
+  typename Derivedpos,
+  typename Derivedmodel,
+  typename Derivedproj,
+  typename Derivedviewport,
+  typename Deriveds,
+  typename Deriveddir>
+IGL_INLINE void igl::unproject_ray(
+  const Eigen::PlainObjectBase<Derivedpos> & pos,
+  const Eigen::PlainObjectBase<Derivedmodel> & model,
+  const Eigen::PlainObjectBase<Derivedproj> & proj,
+  const Eigen::PlainObjectBase<Derivedviewport> & viewport,
+  Eigen::PlainObjectBase<Deriveds> & s,
+  Eigen::PlainObjectBase<Deriveddir> & dir)
+{
+  using namespace igl;
+  using namespace std;
+  using namespace Eigen;
+  // Source and direction on screen
+  typedef Eigen::Matrix<typename Deriveds::Scalar,3,1> Vec3;
+  Vec3 win_s(pos(0),pos(1),0);
+  Vec3 win_d(pos(0),pos(1),1);
+  // Source, destination and direction in world
+  Vec3 d;
+  igl::unproject(win_s,model,proj,viewport,s);
+  igl::unproject(win_d,model,proj,viewport,d);
+  dir = d-s;
+}

+ 44 - 0
include/igl/unproject_ray.h

@@ -0,0 +1,44 @@
+// This file is part of libigl, a simple c++ geometry processing library.
+//
+// Copyright (C) 2015 Alec Jacobson <alecjacobson@gmail.com>
+//
+// 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_UNPROJECT_RAY_H
+#define IGL_UNPROJECT_RAY_H
+#include "igl_inline.h"
+#include <Eigen/Core>
+namespace igl
+{
+  // Construct a ray (source point + direction vector) given a screen space
+  // positions (e.g. mouse) and a model-view projection constellation.
+  //
+  // Inputs:
+  //   pos  2d screen-space position (x,y) 
+  //   model  4x4 model-view matrix
+  //   proj  4x4 projection matrix
+  //   viewport  4-long viewport vector
+  // Outputs:
+  //   s  source of ray (pos unprojected with z=0)
+  ///  dir  direction of ray (d - s) where d is pos unprojected with z=1
+  // 
+  template <
+    typename Derivedpos,
+    typename Derivedmodel,
+    typename Derivedproj,
+    typename Derivedviewport,
+    typename Deriveds,
+    typename Deriveddir>
+  IGL_INLINE void unproject_ray(
+    const Eigen::PlainObjectBase<Derivedpos> & pos,
+    const Eigen::PlainObjectBase<Derivedmodel> & model,
+    const Eigen::PlainObjectBase<Derivedproj> & proj,
+    const Eigen::PlainObjectBase<Derivedviewport> & viewport,
+    Eigen::PlainObjectBase<Deriveds> & s,
+    Eigen::PlainObjectBase<Deriveddir> & dir);
+}
+#ifndef IGL_STATIC_LIBRARY
+#  include "unproject_ray.cpp"
+#endif
+#endif