├── .gitignore ├── .travis.yml ├── CMakeLists.txt ├── CMakeModules ├── CMakeUninstall.cmake.in ├── CPackSettings.cmake ├── CheckIncludeFileCXX.cmake ├── CheckInfNan.cmake ├── CompilerSettings.cmake ├── FindAssimp.cmake ├── FindFreeImage.cmake ├── FindGLPK.cmake ├── FindGLUI.cmake ├── FindGSL.cmake ├── FindKrisLibrary.cmake ├── FindLOG4CXX.cmake ├── FindOMPL.cmake ├── FindTinyXML.cmake ├── InstallPkgConfigFile.cmake ├── KrisLibraryDependencies.cmake └── LibFindMacros.cmake ├── File.cpp ├── File.h ├── GLdraw ├── BoxWidget.cpp ├── BoxWidget.h ├── ColorGradient.cpp ├── ColorGradient.h ├── GL.h ├── GLColor.cpp ├── GLColor.h ├── GLDisplayList.cpp ├── GLDisplayList.h ├── GLError.cpp ├── GLError.h ├── GLFog.cpp ├── GLFog.h ├── GLLight.cpp ├── GLLight.h ├── GLMaterial.cpp ├── GLMaterial.h ├── GLOffscreenContext.cpp ├── GLOffscreenContext.h ├── GLRenderToImage.cpp ├── GLRenderToImage.h ├── GLScreenshot.cpp ├── GLScreenshot.h ├── GLScreenshotProgram.h ├── GLTexture1D.cpp ├── GLTexture1D.h ├── GLTexture2D.cpp ├── GLTexture2D.h ├── GLTextureObject.cpp ├── GLTextureObject.h ├── GLUINavigationProgram.cpp ├── GLUINavigationProgram.h ├── GLUIProgram.cpp ├── GLUIProgram.h ├── GLUTNavigationProgram.cpp ├── GLUTNavigationProgram.h ├── GLUTProgram.cpp ├── GLUTProgram.h ├── GLUTString.h ├── GLView.cpp ├── GLView.h ├── GeometryAppearance.cpp ├── GeometryAppearance.h ├── SphereWidget.cpp ├── SphereWidget.h ├── TransformWidget.cpp ├── TransformWidget.h ├── Widget.cpp ├── Widget.h ├── drawMesh.h ├── drawextra.cpp ├── drawextra.h ├── drawgeometry.cpp └── drawgeometry.h ├── LICENSE ├── LICENSE.txt ├── Logger.cpp ├── Logger.h ├── README.md ├── Timer.cpp ├── Timer.h ├── camera ├── camera.cpp ├── camera.h ├── clip.cpp ├── clip.h ├── frustum.cpp ├── frustum.h ├── transform.cpp ├── transform.h ├── viewport.cpp └── viewport.h ├── doxygen.conf ├── doxygen.conf.in ├── errors.cpp ├── errors.h ├── geometry ├── AnyGeometry.cpp ├── AnyGeometry.h ├── Arrangement1D.cpp ├── Arrangement1D.h ├── BallTree.cpp ├── BallTree.h ├── CollisionConvexHull.cpp ├── CollisionConvexHull.h ├── CollisionHeightmap.cpp ├── CollisionHeightmap.h ├── CollisionImplicitSurface.cpp ├── CollisionImplicitSurface.h ├── CollisionMesh.cpp ├── CollisionMesh.h ├── CollisionOccupancyGrid.cpp ├── CollisionOccupancyGrid.h ├── CollisionPointCloud.cpp ├── CollisionPointCloud.h ├── CollisionPrimitive.cpp ├── CollisionPrimitive.h ├── Conversions.cpp ├── Conversions.h ├── ConvexHull2D.cpp ├── ConvexHull2D.h ├── ConvexHull3D.cpp ├── ConvexHull3D.h ├── DCEL.h ├── Fitting.cpp ├── Fitting.h ├── GeometryType.h ├── GeometryTypeImpl.cpp ├── GeometryTypeImpl.h ├── Grid.cpp ├── Grid.h ├── GridSubdivision.cpp ├── GridSubdivision.h ├── GridTable.h ├── HACD_Lib │ ├── CMakeLists.txt │ ├── inc │ │ ├── hacdCircularList.h │ │ ├── hacdCircularList.inl │ │ ├── hacdGraph.h │ │ ├── hacdHACD.h │ │ ├── hacdICHull.h │ │ ├── hacdManifoldMesh.h │ │ ├── hacdMeshDecimator.h │ │ ├── hacdMicroAllocator.h │ │ ├── hacdRaycastMesh.h │ │ ├── hacdSArray.h │ │ ├── hacdVector.h │ │ ├── hacdVector.inl │ │ └── hacdVersion.h │ └── src │ │ ├── hacdGraph.cpp │ │ ├── hacdHACD.cpp │ │ ├── hacdICHull.cpp │ │ ├── hacdManifoldMesh.cpp │ │ ├── hacdMeshDecimator.cpp │ │ ├── hacdMicroAllocator.cpp │ │ └── hacdRaycastMesh.cpp ├── KDTree.cpp ├── KDTree.h ├── MonotoneChain.cpp ├── MonotoneChain.h ├── MultiVolumeGrid.cpp ├── MultiVolumeGrid.h ├── NeighborGraph.cpp ├── NeighborGraph.h ├── Octree.cpp ├── Octree.h ├── PQP │ ├── Makefile │ ├── PQP.DSP │ ├── PQP.PLG │ ├── PQP.dsw │ ├── README.txt │ ├── demos │ │ ├── Makefile │ │ ├── demos.dsp │ │ ├── demos.dsw │ │ ├── falling │ │ │ ├── Makefile │ │ │ ├── MatVec.h │ │ │ ├── falling.dsp │ │ │ ├── falling.plg │ │ │ ├── main.cpp │ │ │ ├── model.cpp │ │ │ ├── model.h │ │ │ ├── torus1.path │ │ │ ├── torus1.tris │ │ │ ├── torus2.path │ │ │ └── torus2.tris │ │ ├── sample │ │ │ ├── Makefile │ │ │ ├── main.cpp │ │ │ ├── sample.dsp │ │ │ └── sample.plg │ │ └── spinning │ │ │ ├── Makefile │ │ │ ├── MatVec.h │ │ │ ├── bunny.tris │ │ │ ├── main.cpp │ │ │ ├── model.cpp │ │ │ ├── model.h │ │ │ ├── spinning.dsp │ │ │ ├── spinning.plg │ │ │ └── torus.tris │ ├── include │ │ ├── BV.h │ │ ├── PQP.h │ │ ├── PQP_Compile.h │ │ ├── PQP_Internal.h │ │ └── Tri.h │ └── src │ │ ├── BV.cpp │ │ ├── BV.h │ │ ├── BVTQ.h │ │ ├── Build.cpp │ │ ├── Build.h │ │ ├── GetTime.h │ │ ├── MatVec.h │ │ ├── OBB_Disjoint.h │ │ ├── PQP.cpp │ │ ├── PQP.h │ │ ├── PQP_Compile.h │ │ ├── PQP_Internal.h │ │ ├── RectDist.h │ │ ├── Tri.h │ │ ├── TriDist.cpp │ │ └── TriDist.h ├── PenetrationDepth.cpp ├── PenetrationDepth.h ├── PolytopeProjection.cpp ├── PolytopeProjection.h ├── ROI.cpp ├── ROI.h ├── SegmentOverlay.cpp ├── SegmentOverlay.h ├── Slice.cpp ├── Slice.h ├── SparseVolumeGrid.cpp ├── SparseVolumeGrid.h ├── SpiralIterator.cpp ├── SpiralIterator.h ├── TSDFReconstruction.cpp ├── TSDFReconstruction.h ├── UnboundedPolytope2D.cpp ├── UnboundedPolytope2D.h ├── primitives.h ├── rayprimitives.h └── solid3 │ ├── CMakeLists.txt │ ├── CMakeModules │ ├── CMakeParseArguments.cmake │ ├── FindGLUT.cmake │ ├── FindPackageHandleStandardArgs.cmake │ └── FindPackageMessage.cmake │ ├── ChangeLog.txt │ ├── LICENSE_GPL.txt │ ├── LICENSE_QPL.txt │ ├── Makefile.am │ ├── README.md │ ├── configure.ac │ ├── doc │ ├── Makefile.am │ ├── gpl.texi │ ├── qpl.texi │ ├── solid3.pdf │ ├── solid3.texi │ ├── texinfo.tex │ └── version.texi │ ├── examples │ ├── CMakeLists.txt │ ├── Makefile.am │ ├── README.txt │ ├── dynamics │ │ ├── CMakeLists.txt │ │ ├── Dynamic.cpp │ │ ├── Dynamic.h │ │ ├── Kinetic.cpp │ │ ├── Kinetic.h │ │ ├── Makefile.am │ │ ├── RigidBody.cpp │ │ └── RigidBody.h │ ├── gldemo.cpp │ ├── mnm.cpp │ ├── physics.cpp │ └── sample.cpp │ ├── include │ ├── GEN_MinMax.h │ ├── GEN_random.h │ ├── MT │ │ ├── Interval.h │ │ ├── Matrix3x3.h │ │ ├── Quaternion.h │ │ ├── Transform.h │ │ ├── Tuple3.h │ │ ├── Tuple4.h │ │ └── Vector3.h │ ├── MT_BBox.h │ ├── MT_Interval.h │ ├── MT_Matrix3x3.h │ ├── MT_Point3.h │ ├── MT_Quaternion.h │ ├── MT_Scalar.h │ ├── MT_ScalarTracer.h │ ├── MT_Transform.h │ ├── MT_Vector3.h │ ├── Makefile.am │ ├── SOLID.h │ ├── SOLID_broad.h │ ├── SOLID_types.h │ └── qhull │ │ ├── geom.h │ │ ├── io.h │ │ ├── mem.h │ │ ├── merge.h │ │ ├── poly.h │ │ ├── qhull.h │ │ ├── qhull_a.h │ │ ├── qset.h │ │ ├── stat.h │ │ └── user.h │ ├── solid3-config.cmake.in │ └── src │ ├── CMakeLists.txt │ ├── DT_AlgoTable.h │ ├── DT_C-api.cpp │ ├── DT_Encounter.cpp │ ├── DT_Encounter.h │ ├── DT_Object.cpp │ ├── DT_Object.h │ ├── DT_RespTable.cpp │ ├── DT_RespTable.h │ ├── DT_Response.h │ ├── DT_Scene.cpp │ ├── DT_Scene.h │ ├── Makefile.am │ ├── broad │ ├── BP_C-api.cpp │ ├── BP_Endpoint.h │ ├── BP_EndpointList.cpp │ ├── BP_EndpointList.h │ ├── BP_Proxy.cpp │ ├── BP_Proxy.h │ ├── BP_ProxyList.h │ ├── BP_Scene.cpp │ ├── BP_Scene.h │ └── Makefile.am │ ├── complex │ ├── DT_BBoxTree.cpp │ ├── DT_BBoxTree.h │ ├── DT_CBox.h │ ├── DT_Complex.cpp │ ├── DT_Complex.h │ └── Makefile.am │ ├── convex │ ├── DT_Accuracy.cpp │ ├── DT_Accuracy.h │ ├── DT_Array.h │ ├── DT_Box.cpp │ ├── DT_Box.h │ ├── DT_Cone.cpp │ ├── DT_Cone.h │ ├── DT_Convex.cpp │ ├── DT_Convex.h │ ├── DT_Cylinder.cpp │ ├── DT_Cylinder.h │ ├── DT_GJK.h │ ├── DT_Hull.h │ ├── DT_IndexArray.h │ ├── DT_LineSegment.cpp │ ├── DT_LineSegment.h │ ├── DT_Minkowski.h │ ├── DT_PenDepth.cpp │ ├── DT_PenDepth.h │ ├── DT_Point.cpp │ ├── DT_Point.h │ ├── DT_Polyhedron.cpp │ ├── DT_Polyhedron.h │ ├── DT_Polytope.cpp │ ├── DT_Polytope.h │ ├── DT_Shape.h │ ├── DT_Sphere.cpp │ ├── DT_Sphere.h │ ├── DT_Transform.h │ ├── DT_TriEdge.cpp │ ├── DT_TriEdge.h │ ├── DT_Triangle.cpp │ ├── DT_Triangle.h │ ├── DT_VertexBase.h │ └── Makefile.am │ └── qhull │ ├── CMakeLists.txt │ ├── Changes.txt │ ├── MBorland │ ├── Makefile.am │ ├── geom.c │ ├── geom.h │ ├── geom2.c │ ├── global.c │ ├── index.htm │ ├── io.c │ ├── io.h │ ├── mem.c │ ├── mem.h │ ├── merge.c │ ├── merge.h │ ├── poly.c │ ├── poly.h │ ├── poly2.c │ ├── qconvex.c │ ├── qdelaun.c │ ├── qh-geom.htm │ ├── qh-globa.htm │ ├── qh-io.htm │ ├── qh-mem.htm │ ├── qh-merge.htm │ ├── qh-poly.htm │ ├── qh-qhull.htm │ ├── qh-set.htm │ ├── qh-stat.htm │ ├── qh-user.htm │ ├── qhalf.c │ ├── qhull.c │ ├── qhull.h │ ├── qhull_a.h │ ├── qhull_interface.cpp │ ├── qset.c │ ├── qset.h │ ├── qvoronoi.c │ ├── rbox.c │ ├── stat.c │ ├── stat.h │ ├── unix.c │ ├── user.c │ ├── user.h │ ├── user_eg.c │ └── user_eg2.c ├── graph ├── APSP.h ├── ApproximateShortestPaths.h ├── Callback.h ├── ConnectedComponents.h ├── DirectedGraph.h ├── Edge.h ├── Graph.h ├── IO.cpp ├── IO.h ├── Node.h ├── Operations.h ├── Path.h ├── ShortestPaths.h ├── Tree.h └── UndirectedGraph.h ├── image ├── bmp.cpp ├── formats.h ├── gdi.cpp ├── gdi.h ├── image.cpp ├── image.h ├── io.cpp ├── io.h ├── opencv_convert.h ├── ppm.cpp ├── ppm.h ├── textureops.cpp ├── textureops.h └── tga.cpp ├── math ├── AABB.cpp ├── AABB.h ├── ASCIIShade.cpp ├── ASCIIShade.h ├── AngleSet.cpp ├── AngleSet.h ├── BLASInterface.cpp ├── BLASInterface.h ├── BlockPrinter.cpp ├── BlockPrinter.h ├── BlockTridiagonalMatrix.cpp ├── BlockTridiagonalMatrix.h ├── BlockVector.cpp ├── BlockVector.h ├── CholeskyDecomposition.cpp ├── CholeskyDecomposition.h ├── ConditionedConstraint.cpp ├── ConditionedConstraint.h ├── Conditioner.cpp ├── Conditioner.h ├── DiagonalMatrix.cpp ├── DiagonalMatrix.h ├── GramSchmidt.cpp ├── GramSchmidt.h ├── Householder.cpp ├── Householder.h ├── InequalityConstraint.cpp ├── InequalityConstraint.h ├── Interval.h ├── IntervalSet.cpp ├── IntervalSet.h ├── LAPACKInterface.cpp ├── LAPACKInterface.h ├── LDL.cpp ├── LDL.h ├── LUDecomposition.cpp ├── LUDecomposition.h ├── LinearPath.cpp ├── LinearPath.h ├── LinearlyDependent.cpp ├── LinearlyDependent.h ├── MatrixEquationPrinter.cpp ├── MatrixEquationPrinter.h ├── MatrixPrinter.cpp ├── MatrixPrinter.h ├── MatrixTemplate.cpp ├── MatrixTemplate.h ├── QRDecomposition.cpp ├── QRDecomposition.h ├── QuasiNewton.cpp ├── QuasiNewton.h ├── RowEchelon.cpp ├── RowEchelon.h ├── SVDecomposition.cpp ├── SVDecomposition.h ├── SelfTest.cpp ├── SelfTest.h ├── SparseMatrixTemplate.cpp ├── SparseMatrixTemplate.h ├── SparseVectorTemplate.cpp ├── SparseVectorTemplate.h ├── VectorPrinter.cpp ├── VectorPrinter.h ├── VectorTemplate.cpp ├── VectorTemplate.h ├── angle.cpp ├── angle.h ├── backsubstitute.cpp ├── backsubstitute.h ├── brent.cpp ├── brent.h ├── cast.h ├── complex.cpp ├── complex.h ├── conjgrad.h ├── diffeq.cpp ├── diffeq.h ├── differentiation.cpp ├── differentiation.h ├── fastarray.h ├── fastmath.h ├── format.h ├── function.cpp ├── function.h ├── gaussian.cpp ├── gaussian.h ├── indexing.h ├── infnan.cpp ├── infnan.h ├── interpolate.h ├── linalgebra.cpp ├── linalgebra.h ├── math.h ├── matrix.h ├── metric.cpp ├── metric.h ├── misc.cpp ├── misc.h ├── polynomial.h ├── quadrature.cpp ├── quadrature.h ├── random.cpp ├── random.h ├── realfunction.cpp ├── realfunction.h ├── root.cpp ├── root.h ├── sample.cpp ├── sample.h ├── sparsefunction.h ├── sparsematrix.h ├── sparsevector.h ├── specialfunctions.h ├── stacking.h ├── vector.h ├── vectorfunction.cpp └── vectorfunction.h ├── math3d ├── AABB2D.cpp ├── AABB2D.h ├── AABB3D.cpp ├── AABB3D.h ├── AABBTemplate.h ├── Box2D.h ├── Box3D.cpp ├── Box3D.h ├── Circle2D.h ├── Circle3D.cpp ├── Circle3D.h ├── Cylinder3D.cpp ├── Cylinder3D.h ├── Ellipsoid3D.h ├── Line2D.cpp ├── Line2D.h ├── Line3D.cpp ├── Line3D.h ├── LinearAlgebra.cpp ├── LinearAlgebra.h ├── LinearlyDependent.cpp ├── LinearlyDependent.h ├── LocalCoordinates2D.cpp ├── LocalCoordinates2D.h ├── LocalCoordinates3D.cpp ├── LocalCoordinates3D.h ├── Plane2D.h ├── Plane3D.cpp ├── Plane3D.h ├── Point.h ├── Polygon2D.cpp ├── Polygon2D.h ├── Polygon3D.cpp ├── Polygon3D.h ├── Polyhedron3D.cpp ├── Polyhedron3D.h ├── Ray2D.h ├── Ray3D.cpp ├── Ray3D.h ├── Segment2D.cpp ├── Segment2D.h ├── Segment3D.cpp ├── Segment3D.h ├── Sphere3D.h ├── Triangle2D.cpp ├── Triangle2D.h ├── Triangle3D.cpp ├── Triangle3D.h ├── basis.h ├── clip.cpp ├── clip.h ├── geometry2d.cpp ├── geometry2d.h ├── geometry3d.cpp ├── geometry3d.h ├── inlinetypes.h ├── interpolate.cpp ├── interpolate.h ├── matinline.h ├── misc.h ├── polar.cpp ├── polar.h ├── primitives.cpp ├── primitives.h ├── quatinline.cpp ├── quatinline.h ├── random.cpp ├── random.h ├── rotation.cpp ├── rotation.h ├── rotationfit.cpp ├── rotationfit.h └── vecinline.h ├── meshing ├── AreaGrid.cpp ├── AreaGrid.h ├── ClosestPoint.cpp ├── ClosestPoint.h ├── Expand.cpp ├── Expand.h ├── Geodesic.cpp ├── Geodesic.h ├── Heightmap.cpp ├── Heightmap.h ├── IO.cpp ├── IO.h ├── LSConformalMapping.cpp ├── LSConformalMapping.h ├── MarchingCubes.cpp ├── MarchingCubes.h ├── MeshPrimitives.cpp ├── MeshPrimitives.h ├── Meshing.cpp ├── Meshing.h ├── PointCloud.cpp ├── PointCloud.h ├── Rasterize.cpp ├── Rasterize.h ├── TriMesh.cpp ├── TriMesh.h ├── TriMeshAtlas.h ├── TriMeshOperators.cpp ├── TriMeshOperators.h ├── TriMeshTopology.cpp ├── TriMeshTopology.h ├── VolumeGrid.cpp ├── VolumeGrid.h ├── Voxelize.cpp └── Voxelize.h ├── msvc ├── .gitignore ├── KrisLibrary.sln ├── KrisLibrary.vcxproj └── KrisLibrary.vcxproj.filters ├── msvc64 ├── .gitignore ├── ALL_BUILD.vcxproj ├── ALL_BUILD.vcxproj.filters ├── INSTALL.vcxproj ├── INSTALL.vcxproj.filters ├── KrisLibrary.sln ├── KrisLibrary.vcxproj ├── KrisLibrary.vcxproj.filters ├── PACKAGE.vcxproj ├── PACKAGE.vcxproj.filters ├── ZERO_CHECK.vcxproj ├── ZERO_CHECK.vcxproj.filters ├── uninstall.vcxproj └── uninstall.vcxproj.filters ├── optimization ├── BoundedLSQRSolver.cpp ├── BoundedLSQRSolver.h ├── GLPKInterface.cpp ├── GLPKInterface.h ├── LCP.cpp ├── LCP.h ├── LPOptimumFunction.cpp ├── LPOptimumFunction.h ├── LPRobust.cpp ├── LPRobust.h ├── LP_InteriorPoint.cpp ├── LP_InteriorPoint.h ├── LSQRInterface.cpp ├── LSQRInterface.h ├── LeastSquares.cpp ├── LeastSquares.h ├── LinearProgram.cpp ├── LinearProgram.h ├── MinNormProblem.cpp ├── MinNormProblem.h ├── Minimization.cpp ├── Minimization.h ├── Newton.cpp ├── Newton.h ├── NewtonSolver.cpp ├── NewtonSolver.h ├── NonlinearProgram.cpp ├── NonlinearProgram.h ├── QuadProgPPInterface.cpp ├── QuadProgPPInterface.h ├── QuadraticProgram.cpp ├── QuadraticProgram.h ├── RegularizedLinearProgram.cpp ├── RegularizedLinearProgram.h ├── SelfTest.cpp ├── SelfTest.h ├── lsqr.cpp ├── lsqr.h └── optimization.h ├── planning ├── AOMetaPlanner.cpp ├── AOMetaPlanner.h ├── AnyMotionPlanner.cpp ├── AnyMotionPlanner.h ├── CSet.h ├── CSetHelpers.cpp ├── CSetHelpers.h ├── CSpace.cpp ├── CSpace.h ├── CSpaceAnalysis.cpp ├── CSpaceAnalysis.h ├── CSpaceHelpers.cpp ├── CSpaceHelpers.h ├── CVSpace.cpp ├── CVSpace.h ├── ControlSpace.cpp ├── ControlSpace.h ├── CostSpace.cpp ├── CostSpace.h ├── DensityEstimator.cpp ├── DensityEstimator.h ├── DisplacementPlanner.cpp ├── DisplacementPlanner.h ├── DoubleIntegrator.cpp ├── DoubleIntegrator.h ├── EdgePlanner.cpp ├── EdgePlanner.h ├── EdgePlannerHelpers.h ├── FMM.cpp ├── FMM.h ├── FMMMotionPlanner.cpp ├── FMMMotionPlanner.h ├── GeneralizedAStar.h ├── GeneralizedBezierCurve.cpp ├── GeneralizedBezierCurve.h ├── GeodesicSpace.h ├── Geometric2DCSpace.cpp ├── Geometric2DCSpace.h ├── Grid2DCSpace.cpp ├── Grid2DCSpace.h ├── Interpolator.cpp ├── Interpolator.h ├── InterpolatorHelpers.h ├── KinodynamicMotionPlanner.cpp ├── KinodynamicMotionPlanner.h ├── KinodynamicOptimizer.cpp ├── KinodynamicOptimizer.h ├── KinodynamicPath.cpp ├── KinodynamicPath.h ├── KinodynamicSpace.cpp ├── KinodynamicSpace.h ├── MCRPlanner.cpp ├── MCRPlanner.h ├── MCRPlannerGoalSet.cpp ├── MCRPlannerGoalSet.h ├── MotionPlanner.cpp ├── MotionPlanner.h ├── MultiModalCSpace.h ├── MultiModalPlanner.cpp ├── MultiModalPlanner.h ├── MultiRobot2DCSpace.cpp ├── MultiRobot2DCSpace.h ├── OMPLInterface.cpp ├── OMPLInterface.h ├── Objective.cpp ├── Objective.h ├── OptimalMotionPlanner.cpp ├── OptimalMotionPlanner.h ├── PRT.h ├── ParabolicRamp.cpp ├── ParabolicRamp.h ├── ParabolicRampConfig.h ├── Path.cpp ├── Path.h ├── PerturbationCSpace.cpp ├── PerturbationCSpace.h ├── PointLocation.cpp ├── PointLocation.h ├── RigidBodyCSpace.cpp ├── RigidBodyCSpace.h ├── RigidRobot2DCSpace.cpp ├── RigidRobot2DCSpace.h ├── RigidRobot3DCSpace.h ├── SBL.cpp ├── SBL.h ├── SBLTree.cpp ├── SBLTree.h ├── SteeringFunction.h ├── Tabular.cpp ├── Tabular.h ├── TimeCSpace.cpp ├── TimeCSpace.h ├── TimedPath.cpp ├── TimedPath.h ├── TranslatingRobot2DCSpace.cpp ├── TranslatingRobot2DCSpace.h ├── VisibilityGraphPlanner.cpp └── VisibilityGraphPlanner.h ├── robotics ├── AnalyticIK.cpp ├── AnalyticIK.h ├── AngleBracket.cpp ├── AngleBracket.h ├── CartesianDrive.cpp ├── CartesianDrive.h ├── Chain.cpp ├── Chain.h ├── ConstrainedDynamics.cpp ├── ConstrainedDynamics.h ├── Contact.cpp ├── Contact.h ├── DenavitHartenberg.cpp ├── DenavitHartenberg.h ├── DynamicChain.cpp ├── DynamicChain.h ├── DynamicChain3D.cpp ├── DynamicChain3D.h ├── Frame.h ├── Geometry.cpp ├── Geometry.h ├── IK.cpp ├── IK.h ├── IKFunctions.cpp ├── IKFunctions.h ├── Inertia.cpp ├── Inertia.h ├── JointStructure.cpp ├── JointStructure.h ├── KinematicChain.cpp ├── KinematicChain.h ├── KinematicChain3D.cpp ├── KinematicChain3D.h ├── Kinematics.cpp ├── Kinematics.h ├── NewtonEuler.cpp ├── NewtonEuler.h ├── RLG.cpp ├── RLG.h ├── RigidBodyDynamics.cpp ├── RigidBodyDynamics.h ├── RobotDynamics3D.cpp ├── RobotDynamics3D.h ├── RobotKinematics3D.cpp ├── RobotKinematics3D.h ├── RobotLink3D.cpp ├── RobotLink3D.h ├── RobotWithGeometry.cpp ├── RobotWithGeometry.h ├── Rotation.cpp ├── Rotation.h ├── SelfTest.cpp ├── SelfTest.h ├── Simulate.cpp ├── Simulate.h ├── SolvingTorques.txt ├── Stability.cpp ├── Stability.h ├── TorqueSolver.cpp ├── TorqueSolver.h ├── WorkspaceBound.cpp ├── WorkspaceBound.h └── Wrench.h ├── spline ├── BSpline.cpp ├── BSpline.h ├── Hermite.cpp ├── Hermite.h ├── MonotonicSpline.cpp ├── MonotonicSpline.h ├── PiecewisePolynomial.cpp ├── PiecewisePolynomial.h ├── Polynomial.h ├── TimeSegmentation.h ├── basis.cpp ├── basis.h ├── path.cpp ├── path.h ├── spline.cpp └── spline.h ├── statistics ├── BernoulliDistribution.h ├── BetaDistribution.cpp ├── BetaDistribution.h ├── CategoricalDistribution.cpp ├── CategoricalDistribution.h ├── DataSet.cpp ├── DataSet.h ├── DiracDistribution.h ├── DistributionCollector.cpp ├── DistributionCollector.h ├── GaussianDistribution.cpp ├── GaussianDistribution.h ├── GaussianHMM.cpp ├── GaussianHMM.h ├── GaussianMixtureModel.cpp ├── GaussianMixtureModel.h ├── HierarchicalClustering.cpp ├── HierarchicalClustering.h ├── Histogram.cpp ├── Histogram.h ├── Histogram2D.h ├── Histogram3D.h ├── HistogramND.cpp ├── HistogramND.h ├── IntervalMap.h ├── KMeans.cpp ├── KMeans.h ├── LinearModel.cpp ├── LinearModel.h ├── LinearProcessHMM.cpp ├── LinearProcessHMM.h ├── LogisticModel.cpp ├── LogisticModel.h ├── OLS.cpp ├── OLS.h ├── OnlineLASSO.h ├── OnlineMoments.cpp ├── OnlineMoments.h ├── OnlineOLS.cpp ├── OnlineOLS.h ├── ProbabilityDistribution.h ├── StatDatabase.h ├── UniformDistribution.cpp ├── UniformDistribution.h ├── WeibullDistribution.h ├── statistics.cpp └── statistics.h ├── structs ├── FastFindHeap.h ├── FixedSizeHeap.h ├── Heap.h ├── IndexedPriorityQueue.h ├── RedBlack.h ├── SparseArray.h ├── array2d.h ├── array3d.h ├── arraynd.h └── priority_queue2.h ├── utils.h └── utils ├── AnyCollection.cpp ├── AnyCollection.h ├── AnyMapper.cpp ├── AnyMapper.h ├── AnyValue.h ├── ArrayMapping.h ├── AsyncIO.cpp ├── AsyncIO.h ├── CommandLine.cpp ├── CommandLine.h ├── ContextStack.h ├── CoverSet.cpp ├── CoverSet.h ├── DirtyData.h ├── EZTrace.cpp ├── EZTrace.h ├── EquivalenceMap.h ├── FastSampler.h ├── IndexSet.cpp ├── IndexSet.h ├── IntPair.cpp ├── IntPair.h ├── IntTriple.cpp ├── IntTriple.h ├── IntTuple.h ├── ParamList.cpp ├── ParamList.h ├── PrimitiveValue.cpp ├── PrimitiveValue.h ├── ProgressPrinter.cpp ├── ProgressPrinter.h ├── PropertyMap.cpp ├── PropertyMap.h ├── RangeMap.h ├── RangeMap2D.h ├── RangeSet.cpp ├── RangeSet.h ├── RangeSet2D.cpp ├── RangeSet2D.h ├── ResourceLibrary.cpp ├── ResourceLibrary.h ├── SignalHandler.cpp ├── SignalHandler.h ├── SimpleFile.cpp ├── SimpleFile.h ├── SimpleParser.cpp ├── SimpleParser.h ├── SmartPointer.h ├── StatCollector.cpp ├── StatCollector.h ├── Subset.cpp ├── Subset.h ├── Trace.cpp ├── Trace.h ├── apputils.cpp ├── apputils.h ├── arrayutils.h ├── bits.h ├── cmp_func.h ├── combination.h ├── fileutils.cpp ├── fileutils.h ├── indexing.cpp ├── indexing.h ├── ioutils.cpp ├── ioutils.h ├── iteratorutils.h ├── permutation.h ├── random.h ├── shift.h ├── socketutils.cpp ├── socketutils.h ├── stl_tr1.h ├── stringutils.cpp ├── stringutils.h ├── threadutils.cpp ├── threadutils.h ├── unionfind.cpp └── unionfind.h /.gitignore: -------------------------------------------------------------------------------- 1 | .vscode 2 | CMakeDoxyfile.in 3 | CMakeDoxygenDefaults.cmake 4 | 5 | # Compiled source # 6 | ################### 7 | *.com 8 | *.class 9 | *.dll 10 | *.exe 11 | *.o 12 | *.so 13 | 14 | # Packages # 15 | ############ 16 | # it's better to unpack these files and commit the raw source 17 | # git has its own built in compression methods 18 | *.7z 19 | *.dmg 20 | *.gz 21 | *.iso 22 | *.jar 23 | *.rar 24 | *.tar 25 | *.zip 26 | 27 | # Logs and databases # 28 | ###################### 29 | *.log 30 | *.sql 31 | *.sqlite 32 | 33 | # OS generated files # 34 | ###################### 35 | .DS_Store 36 | .DS_Store? 37 | ._* 38 | .Spotlight-V100 39 | .Trashes 40 | ehthumbs.db 41 | Thumbs.db 42 | 43 | 44 | # temporary compilation files # 45 | ###################### 46 | Documentation 47 | deps 48 | objs 49 | lib 50 | *.a 51 | 52 | #Windows files 53 | msvc 54 | Debug 55 | Debug-Assimp 56 | Release 57 | Release-Assimp 58 | x64 59 | 60 | #CMake temporary files 61 | Makefile 62 | CMakeFiles 63 | CMakeCache.txt 64 | CPack* 65 | CTest* 66 | cmake*.cmake 67 | _CPack* -------------------------------------------------------------------------------- /.travis.yml: -------------------------------------------------------------------------------- 1 | # Enable C++ support 2 | language: cpp 3 | # Compiler selection 4 | compiler: 5 | - clang 6 | - gcc 7 | # Ubuntu 16.04+ is required 8 | dist: xenial 9 | # Build steps 10 | script: 11 | - cmake . && make 12 | addons: 13 | apt: 14 | packages: 15 | - cmake 16 | - freeglut3 17 | - freeglut3-dev 18 | - libxmu-dev 19 | - libxi-dev 20 | - libglpk-dev 21 | - liblog4cxx10-dev 22 | - libglew-dev 23 | - libassimp-dev 24 | 25 | 26 | -------------------------------------------------------------------------------- /CMakeModules/CMakeUninstall.cmake.in: -------------------------------------------------------------------------------- 1 | if (NOT EXISTS "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt") 2 | message(FATAL_ERROR "Cannot find install manifest: \"@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt\"") 3 | endif(NOT EXISTS "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt") 4 | 5 | file(READ "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt" files) 6 | string(REGEX REPLACE "\n" ";" files "${files}") 7 | list(REVERSE files) 8 | foreach (file ${files}) 9 | message(STATUS "Uninstalling \"$ENV{DESTDIR}${file}\"") 10 | if (EXISTS "$ENV{DESTDIR}${file}") 11 | execute_process( 12 | COMMAND @CMAKE_COMMAND@ -E remove "$ENV{DESTDIR}${file}" 13 | OUTPUT_VARIABLE rm_out 14 | RESULT_VARIABLE rm_retval 15 | ) 16 | if(NOT ${rm_retval} EQUAL 0) 17 | message(FATAL_ERROR "Problem when removing \"$ENV{DESTDIR}${file}\"") 18 | endif (NOT ${rm_retval} EQUAL 0) 19 | else (EXISTS "$ENV{DESTDIR}${file}") 20 | message(STATUS "File \"$ENV{DESTDIR}${file}\" does not exist.") 21 | endif (EXISTS "$ENV{DESTDIR}${file}") 22 | endforeach(file) 23 | -------------------------------------------------------------------------------- /CMakeModules/CPackSettings.cmake: -------------------------------------------------------------------------------- 1 | # Package building stuff - Set CPACK_GENERATOR to whatever package type 2 | # you wish to build... 3 | SET(CPACK_PACKAGE_VERSION "${KRISLIBRARY_VERSION}") 4 | SET(CPACK_PACKAGE_VERSION_MAJOR "${KRISLIBRARY_MAJOR_VERSION}") 5 | SET(CPACK_PACKAGE_VERSION_MINOR "${KRISLIBRARY_MINOR_VERSION}") 6 | SET(CPACK_PACKAGE_VERSION_PATCH "${KRISLIBRARY_PATCH_VERSION}") 7 | #SET(CPACK_PACKAGE_INSTALL_DIRECTORY "KrisLibrary ${V_MAJOR}.${V_MINOR}") 8 | SET(CPACK_PACKAGE_INSTALL_DIRECTORY "KrisLibrary") 9 | SET(CPACK_PACKAGE_CONTACT "K. Hauser") 10 | SET(CPACK_PACKAGE_VENDOR "Indiana University") 11 | SET(CPACK_RESOURCE_FILE_LICENSE "${PROJECT_SOURCE_DIR}/LICENSE.txt") 12 | IF(WIN32) 13 | SET(CPACK_GENERATOR "WIX") 14 | SET(CPACK_WIX_UPGRADE_GUID 80F4492E-C8E2-4785-BF7F-E0AD711AE4E6) 15 | SET(CPACK_SOURCE_GENERATOR "ZIP") 16 | SET(CPACK_SOURCE_PACKAGE_FILE_NAME 17 | "${PROJECT_NAME}-${CPACK_PACKAGE_VERSION_MAJOR}.${CPACK_PACKAGE_VERSION_MINOR}.${CPACK_PACKAGE_VERSION_PATCH}") 18 | ELSE(WIN32) 19 | SET(CPACK_GENERATOR "DEB") 20 | SET(CPACK_SOURCE_GENERATOR "TGZ") 21 | SET(CPACK_SOURCE_PACKAGE_FILE_NAME 22 | "${PROJECT_NAME}-${CPACK_PACKAGE_VERSION_MAJOR}.${CPACK_PACKAGE_VERSION_MINOR}.${CPACK_PACKAGE_VERSION_PATCH}") 23 | ENDIF(WIN32) 24 | 25 | # This must always be last statement! 26 | INCLUDE(CPack) 27 | 28 | -------------------------------------------------------------------------------- /CMakeModules/CheckInfNan.cmake: -------------------------------------------------------------------------------- 1 | INCLUDE(CheckCXXSourceCompiles) 2 | INCLUDE(CheckIncludeFileCXX) 3 | 4 | MACRO(CHECK_FN_OR_MACRO_EXISTS _SYMBOL _HEADER _RESULT) 5 | SET(_INCLUDE_FILES) 6 | FOREACH(it ${_HEADER}) 7 | SET(_INCLUDE_FILES "${_INCLUDE_FILES}#include <${it}>\n") 8 | ENDFOREACH(it) 9 | 10 | SET(_CHECK_PROTO_EXISTS_SOURCE_CODE " 11 | ${_INCLUDE_FILES} 12 | int main() 13 | { 14 | #ifndef ${_SYMBOL} 15 | int i = $(_SYMBOL)(0); 16 | #endif 17 | return 0; 18 | } 19 | ") 20 | CHECK_CXX_SOURCE_COMPILES("${_CHECK_PROTO_EXISTS_SOURCE_CODE}" ${_RESULT}) 21 | ENDMACRO(CHECK_FN_OR_MACRO_EXISTS _SYMBOL _HEADER _RESULT) 22 | 23 | # TODO: determine dynamically whether is defined 24 | CHECK_INCLUDE_FILE_CXX("cmath" HAS_STD_CMATH) 25 | 26 | CHECK_FN_OR_MACRO_EXISTS(isinf "math.h" HAS_DECL_ISINF) 27 | CHECK_FN_OR_MACRO_EXISTS(isnan "math.h" HAS_DECL_ISNAN) 28 | CHECK_FN_OR_MACRO_EXISTS(isfinite "math.h" HAS_DECL_ISFINITE) 29 | CHECK_FN_OR_MACRO_EXISTS(finite "math.h" HAS_DECL_FINITE) 30 | 31 | # TODO: determine dynamically whether IEEE finite/nan comparisons are supported 32 | SET(HAS_IEEE_COMPARISONS TRUE) 33 | -------------------------------------------------------------------------------- /CMakeModules/CompilerSettings.cmake: -------------------------------------------------------------------------------- 1 | # COMPILER SETTINGS (default: Release) 2 | # use "-DCMAKE_BUILD_TYPE=Debug" in cmake for a Debug-build 3 | IF(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE) 4 | SET(CMAKE_BUILD_TYPE Release) 5 | ENDIF(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE) 6 | 7 | MESSAGE ("\n") 8 | MESSAGE (STATUS "${PROJECT_NAME} building as ${CMAKE_BUILD_TYPE}") 9 | 10 | # COMPILER FLAGS 11 | IF (CMAKE_COMPILER_IS_GNUCC) 12 | SET (CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -Wno-error ") 13 | SET (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wno-error ") 14 | SET (CMAKE_CXX_FLAGS_RELEASE "-O3 -funroll-loops -DNDEBUG") 15 | SET (CMAKE_CXX_FLAGS_DEBUG "-O0 -g") 16 | # Shared object compilation under 64bit (vtable) 17 | ADD_DEFINITIONS(-fPIC) 18 | ENDIF() 19 | 20 | IF(MSVC) 21 | #These are used to be compatible with Klampt 22 | SET (CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS} /MD") 23 | SET (CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS} /MD") 24 | SET (CMAKE_C_FLAGS_DEBUG "${CMAKE_C_FLAGS} /MDd") 25 | SET (CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS} /MDd") 26 | ENDIF() 27 | 28 | SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17") 29 | 30 | # Set full rpath http://www.paraview.org/Wiki/CMake_RPATH_handling 31 | # (good to have and required with ROS) 32 | set(CMAKE_SKIP_BUILD_RPATH FALSE) 33 | set(CMAKE_BUILD_WITH_INSTALL_RPATH FALSE) 34 | set(CMAKE_INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/lib") 35 | set(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE) 36 | 37 | # no prefix needed for python modules 38 | set(CMAKE_SHARED_MODULE_PREFIX "") 39 | -------------------------------------------------------------------------------- /CMakeModules/FindFreeImage.cmake: -------------------------------------------------------------------------------- 1 | # -*- mode: cmake -*- 2 | # 3 | # Looks for CMake variable FreeImage_ROOT 4 | # 5 | # this files defines 6 | # - FreeImage_INCLUDE_DIR 7 | # - FreeImage_LIBRARY 8 | # - FreeImage_FOUND 9 | 10 | INCLUDE(CheckIncludeFileCXX) 11 | CHECK_INCLUDE_FILE_CXX(FreeImage.h FreeImage_FOUND) 12 | 13 | IF(WIN32) 14 | #not available on windows 15 | ELSE (WIN32) 16 | FIND_LIBRARY( FreeImage_LIBRARY freeimage PATHS /usr/lib ${FreeImage_ROOT}/lib) 17 | 18 | FIND_PATH(FreeImage_INCLUDE_DIR 19 | FreeImage.h 20 | PATHS /usr/include/ /usr/include/FreeImage ${FreeImage_ROOT}/include 21 | DOC "Directory where FreeImage header files are stored" ) 22 | ENDIF(WIN32) 23 | 24 | include(FindPackageHandleStandardArgs) 25 | find_package_handle_standard_args(FreeImage "Could not find FreeImage " FreeImage_INCLUDE_DIR FreeImage_LIBRARY) 26 | # show the FreeImage_INCLUDE_DIR and FreeImage_LIBRARY variables only in the advanced view 27 | MARK_AS_ADVANCED(FreeImage_INCLUDE_DIR FreeImage_LIBRARY ) 28 | 29 | -------------------------------------------------------------------------------- /CMakeModules/FindOMPL.cmake: -------------------------------------------------------------------------------- 1 | # - Find Open Motion Planning Library 2 | # Find the native OMPL includes and library 3 | # 4 | # OMPL_FOUND - True if OMPL found. 5 | # OMPL_INCLUDE_DIR - where to find OMPL.h, etc. 6 | # OMPL_LIBRARIES - List of libraries when using OMPL. 7 | # 8 | 9 | IF( OMPL_INCLUDE_DIR ) 10 | # Already in cache, be silent 11 | SET( OMPL_FIND_QUIETLY TRUE ) 12 | ENDIF( OMPL_INCLUDE_DIR ) 13 | 14 | FIND_PATH( OMPL_INCLUDE_DIR "ompl/config.h" 15 | PATHS ${OMPL_ROOT} ) 16 | 17 | FIND_LIBRARY( OMPL_LIBRARIES 18 | NAMES "ompl" 19 | PATHS ${OMPL_ROOT} ) 20 | 21 | # handle the QUIETLY and REQUIRED arguments and set OMPL_FOUND to TRUE if 22 | # all listed variables are TRUE 23 | INCLUDE( "FindPackageHandleStandardArgs" ) 24 | FIND_PACKAGE_HANDLE_STANDARD_ARGS( "OMPL" DEFAULT_MSG OMPL_INCLUDE_DIR OMPL_LIBRARIES ) 25 | 26 | MARK_AS_ADVANCED( OMPL_INCLUDE_DIR OMPL_LIBRARIES ) 27 | 28 | -------------------------------------------------------------------------------- /CMakeModules/FindTinyXML.cmake: -------------------------------------------------------------------------------- 1 | # - Find TinyXML 2 | # Find the native TinyXML includes and library 3 | # 4 | # TINYXML_FOUND - True if TinyXML found. 5 | # TINYXML_INCLUDE_DIR - where to find tinyxml.h, etc. 6 | # TINYXML_LIBRARY - List of libraries when using TinyXML. 7 | # 8 | 9 | IF( TINYXML_INCLUDE_DIR ) 10 | # Already in cache, be silent 11 | SET( TinyXML_FIND_QUIETLY TRUE ) 12 | ENDIF( TINYXML_INCLUDE_DIR ) 13 | 14 | FIND_PATH( TINYXML_INCLUDE_DIR "tinyxml.h" 15 | PATHS ${TINYXML_ROOT} ${TINYXML_ROOT}/tinyxml) 16 | 17 | IF(WIN32) 18 | FIND_LIBRARY( TINYXML_LIBRARY_RELEASE 19 | NAMES "tinyxml_STL" 20 | PATHS ${TINYXML_ROOT} ${TINYXML_ROOT}/Release_STL ) 21 | FIND_LIBRARY( TINYXML_LIBRARY_DEBUG 22 | NAMES "tinyxmld_STL" 23 | PATHS ${TINYXML_ROOT} ${TINYXML_ROOT}/Debug_STL ) 24 | 25 | #this is used to pick between RELEASE and DEBUG library 26 | include(SelectLibraryConfigurations) 27 | select_library_configurations(TINYXML) 28 | ELSE(WIN32) 29 | FIND_LIBRARY( TINYXML_LIBRARY 30 | NAMES "tinyxml" 31 | PATHS ${TINYXML_ROOT} ) 32 | ENDIF(WIN32) 33 | 34 | # handle the QUIETLY and REQUIRED arguments and set TINYXML_FOUND to TRUE if 35 | # all listed variables are TRUE 36 | INCLUDE( "FindPackageHandleStandardArgs" ) 37 | FIND_PACKAGE_HANDLE_STANDARD_ARGS( "TinyXML" DEFAULT_MSG TINYXML_INCLUDE_DIR TINYXML_LIBRARY ) 38 | 39 | MARK_AS_ADVANCED( TINYXML_INCLUDE_DIR TINYXML_LIBRARY ) 40 | 41 | -------------------------------------------------------------------------------- /GLdraw/ColorGradient.cpp: -------------------------------------------------------------------------------- 1 | #include "ColorGradient.h" 2 | #include 3 | 4 | using namespace GLDraw; 5 | 6 | ColorGradient::ColorGradient() 7 | {} 8 | 9 | ColorGradient::ColorGradient(const GLColor& a) 10 | { 11 | SetConstant(a); 12 | } 13 | 14 | ColorGradient::ColorGradient(const GLColor& a,const GLColor& b) 15 | { 16 | SetBlend(a,b); 17 | } 18 | 19 | void ColorGradient::SetConstant(const GLColor& c) 20 | { 21 | params.resize(1); 22 | colors.resize(1); 23 | params[0] = 0; 24 | colors[0] = c; 25 | } 26 | 27 | void ColorGradient::SetBlend(const GLColor& a,const GLColor& b) 28 | { 29 | params.resize(2); 30 | colors.resize(2); 31 | params[0] = 0; 32 | colors[0] = a; 33 | params[1] = 1; 34 | colors[1] = b; 35 | } 36 | 37 | void ColorGradient::SetHue(float hue) 38 | { 39 | for(size_t i=0;i 6 | 7 | namespace GLDraw { 8 | 9 | struct ColorGradient 10 | { 11 | ColorGradient(); 12 | ColorGradient(const GLColor& a); 13 | ColorGradient(const GLColor& a,const GLColor& b); 14 | void SetConstant(const GLColor& c); 15 | void SetBlend(const GLColor& a,const GLColor& b); 16 | void SetHue(float hue); 17 | void SetAlpha(float alpha); 18 | void Eval(float u,GLColor& c) const; 19 | 20 | std::vector params; 21 | std::vector colors; 22 | }; 23 | 24 | } //namespace GLDraw 25 | 26 | #endif 27 | 28 | -------------------------------------------------------------------------------- /GLdraw/GL.h: -------------------------------------------------------------------------------- 1 | #ifndef SCENELIB_GL_H 2 | #define SCENELIB_GL_H 3 | 4 | #ifdef _WIN32 5 | //#define WIN32_LEAN_AND_MEAN 6 | #include 7 | #endif // _WIN32 8 | 9 | #if defined (__APPLE__) || defined (MACOSX) 10 | #define GL_SILENCE_DEPRECATION //helpful to avoid huge number of deprecation warnings 11 | #include 12 | #else 13 | #include 14 | #endif 15 | 16 | #include 17 | 18 | /* 19 | //fix this later 20 | #define GL_GLEXT_PROTOTYPES 21 | #if defined (__APPLE__) || defined (MACOSX) 22 | #include 23 | #else 24 | #include 25 | #endif 26 | */ 27 | 28 | 29 | /** @defgroup GLDraw 30 | * @brief OpenGL, GLUT, and GLUI drawing routines 31 | */ 32 | 33 | 34 | /** @ingroup GLDraw 35 | * @brief Contains all definitions in the GLDraw package 36 | */ 37 | namespace GLDraw { 38 | } //namespace GLDraw 39 | 40 | #endif 41 | -------------------------------------------------------------------------------- /GLdraw/GLDisplayList.h: -------------------------------------------------------------------------------- 1 | #ifndef GL_DISPLAY_LIST_H 2 | #define GL_DISPLAY_LIST_H 3 | 4 | #include 5 | 6 | namespace GLDraw { 7 | 8 | struct GLDisplayList 9 | { 10 | explicit GLDisplayList(int count=1); 11 | GLDisplayList(const GLDisplayList& rhs)=default; 12 | ~GLDisplayList(); 13 | operator bool() const { return isCompiled(); } 14 | GLDisplayList& operator = (const GLDisplayList& rhs)=default; 15 | bool isCompiled() const; 16 | void beginCompile(int index=0); 17 | void beginCompileAndExecute(int index=0); 18 | void endCompile(); 19 | void call(int index=0) const; 20 | void callAll() const; 21 | void erase(); 22 | 23 | std::shared_ptr id; 24 | int count; 25 | }; 26 | 27 | } //namespace GLDraw 28 | 29 | #endif 30 | 31 | 32 | -------------------------------------------------------------------------------- /GLdraw/GLError.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "GLError.h" 3 | #include 4 | #include 5 | using namespace std; 6 | 7 | const char* GLErrorString(GLenum err) 8 | { 9 | switch(err) { 10 | case GL_NO_ERROR: return "GL_NO_ERROR"; 11 | case GL_INVALID_ENUM: return "GL_INVALID_ENUM"; 12 | case GL_INVALID_VALUE: return "GL_INVALID_VALUE"; 13 | case GL_INVALID_OPERATION: return "GL_INVALID_OPERATION"; 14 | case GL_STACK_OVERFLOW: return "GL_STACK_OVERFLOW"; 15 | case GL_STACK_UNDERFLOW: return "GL_STACK_UNDERFLOW"; 16 | case GL_OUT_OF_MEMORY: return "GL_OUT_OF_MEMORY"; 17 | //case GL_TABLE_TOO_LARGE: return "GL_TABLE_TOO_LARGE"; 18 | default: return "GLErrorString(): invalid error code"; 19 | } 20 | } 21 | 22 | bool CheckGLErrors(const char* name,bool pause) 23 | { 24 | bool res=false; 25 | GLenum err; 26 | while((err=glGetError()) != GL_NO_ERROR) { 27 | LOG4CXX_ERROR(KrisLibrary::logger(),name<<" "< 5 | #include "GL.h" 6 | 7 | //Returns the string corresponding to the GL error code err 8 | const char* GLErrorString(GLenum err); 9 | 10 | //Checks for GL errors, prints them with the header string name, 11 | //pauses if pause=true. Returns false if no error occurred. 12 | bool CheckGLErrors(const char* name="GL error",bool pause=true); 13 | 14 | #define GL_ERROR_QUIT 0 15 | #define DEBUG_GL_ERRORS() { \ 16 | GLenum err; \ 17 | while((err=glGetError()) != GL_NO_ERROR) { \ 18 | LOG4CXX_ERROR(KrisLibrary::logger(),"glError "< 6 | 7 | namespace GLDraw { 8 | 9 | using namespace Math; 10 | 11 | class GLFog 12 | { 13 | public: 14 | enum Type { None, Linear, Exponential, ExponentialSquared }; 15 | 16 | GLFog(); 17 | 18 | void setNone(); 19 | void setLinear(Real start, Real end); 20 | void setExponential(Real density); 21 | void setExponentialSquared(Real density); 22 | void setCurrent(); 23 | void unsetCurrent(); 24 | 25 | Type type; 26 | GLColor color; 27 | Real start,end; 28 | Real density; 29 | }; 30 | 31 | } //namespace GLDraw 32 | 33 | #endif 34 | -------------------------------------------------------------------------------- /GLdraw/GLLight.h: -------------------------------------------------------------------------------- 1 | #ifndef GL_LIGHT_H 2 | #define GL_LIGHT_H 3 | 4 | #include "GLColor.h" 5 | #include 6 | 7 | namespace GLDraw { 8 | 9 | using namespace Math3D; 10 | 11 | /** @ingroup GLDraw 12 | * @brief An OpenGL light. 13 | */ 14 | class GLLight 15 | { 16 | public: 17 | GLLight(); 18 | GLLight(const Vector3& direction); 19 | GLLight(const Vector3& position,const Vector3& direction); 20 | GLLight(const GLLight& light); 21 | 22 | void setColor(const GLColor& col); 23 | void setPointLight(const Vector3& pos); 24 | void setDirectionalLight(const Vector3& dir); 25 | void setSpotLight(const Vector3& pos,const Vector3& dir,float exponent=0,float cutoff=180); 26 | 27 | void setCurrentGL(const int id=0); 28 | 29 | Vector4 position; 30 | float att2,att1,att0; //quadratic,linear,constant attenuation 31 | GLColor diffuse, specular; 32 | Vector3 spot_direction; 33 | float spot_exponent,spot_cutoff; 34 | }; 35 | 36 | } //namespace GLDraw 37 | 38 | #endif 39 | -------------------------------------------------------------------------------- /GLdraw/GLMaterial.cpp: -------------------------------------------------------------------------------- 1 | #include "GLMaterial.h" 2 | 3 | using namespace GLDraw; 4 | 5 | GLMaterial::GLMaterial() 6 | :specularExponent(0) 7 | {} 8 | 9 | void GLMaterial::setCurrentGL(GLenum tgt) const 10 | { 11 | glMaterialfv(tgt, GL_AMBIENT, ambient.rgba); 12 | glMaterialfv(tgt, GL_DIFFUSE, diffuse.rgba); 13 | glMaterialfv(tgt, GL_SPECULAR, specular.rgba); 14 | glMaterialf(tgt, GL_SHININESS, specularExponent); 15 | glMaterialfv(tgt, GL_EMISSION, emission.rgba); 16 | } 17 | 18 | 19 | void GLMaterial::setCurrentGL_Front() const 20 | { 21 | setCurrentGL(GL_FRONT); 22 | } 23 | 24 | 25 | void GLMaterial::setCurrentGL_Back() const 26 | { 27 | setCurrentGL(GL_BACK); 28 | } 29 | 30 | void GLMaterial::setCurrentGL_FrontAndBack() const 31 | { 32 | setCurrentGL(GL_FRONT_AND_BACK); 33 | } 34 | -------------------------------------------------------------------------------- /GLdraw/GLMaterial.h: -------------------------------------------------------------------------------- 1 | #ifndef GL_MATERIAL_H 2 | #define GL_MATERIAL_H 3 | 4 | #include "GL.h" 5 | #include "GLColor.h" 6 | 7 | namespace GLDraw { 8 | 9 | /** @ingroup GLDraw 10 | * @brief An OpenGL material. 11 | */ 12 | struct GLMaterial 13 | { 14 | GLMaterial(); 15 | void setCurrentGL(GLenum tgt = GL_FRONT) const; 16 | void setCurrentGL_Front() const; 17 | void setCurrentGL_Back() const; 18 | void setCurrentGL_FrontAndBack() const; 19 | 20 | GLColor ambient, diffuse, specular, emission; 21 | GLfloat specularExponent; 22 | }; 23 | 24 | } //namespace GLDraw 25 | 26 | #endif 27 | -------------------------------------------------------------------------------- /GLdraw/GLOffscreenContext.h: -------------------------------------------------------------------------------- 1 | #ifndef _GLDRAW_OFFSCREEN_CONTEXT_H 2 | #define _GLDRAW_OFFSCREEN_CONTEXT_H 3 | 4 | namespace GLDraw { 5 | 6 | /** @ingroup GLDraw 7 | * @brief A way to draw to an offscreen buffer. Currently only works with XWindows. 8 | * 9 | * To play nicely with other methods of setting up a context, you can first call the 10 | * hasGLContext static function to check whether there's another context available, 11 | * and possibly use that instead. If you really want to use multiple contexts, you 12 | * should restore your other context after you are done rendering. (This is highly 13 | * platform dependent, and may not be available with GLUT). 14 | */ 15 | class GLOffscreenContext 16 | { 17 | public: 18 | GLOffscreenContext(); 19 | ~GLOffscreenContext(); 20 | bool setup(); 21 | void destroy(); 22 | bool makeCurrent(); 23 | 24 | static bool hasGLContext(); 25 | 26 | void* data; //opaque pointer 27 | }; 28 | 29 | } //namespace GLDraw 30 | 31 | #endif 32 | 33 | -------------------------------------------------------------------------------- /GLdraw/GLScreenshot.h: -------------------------------------------------------------------------------- 1 | #ifndef GL_SCREENSHOT_H 2 | #define GL_SCREENSHOT_H 3 | 4 | /** @ingroup GLDraw 5 | * @brief Saves the current back buffer to filename. 6 | * 7 | * If GDI is available (windows) saves to whatever file type is 8 | * given by filename. Otherwise this saves in PPM format. 9 | */ 10 | bool GLSaveScreenshot(const char *filename); 11 | bool GLSaveScreenshotPPM(const char *filename); 12 | 13 | #endif 14 | -------------------------------------------------------------------------------- /GLdraw/GLTexture1D.h: -------------------------------------------------------------------------------- 1 | #ifndef GL_TEXTURE_1D_H 2 | #define GL_TEXTURE_1D_H 3 | 4 | #include "GLTextureObject.h" 5 | #include "ColorGradient.h" 6 | 7 | namespace GLDraw { 8 | 9 | /** @ingroup GLDraw 10 | * @brief 1D texture data for use in OpenGL. 11 | */ 12 | class GLTexture1D 13 | { 14 | public: 15 | GLTexture1D(); 16 | void setLuminance(const unsigned char* data,int n); 17 | void setRGB(const unsigned char* data,int n); 18 | void setRGBA(const unsigned char* data,int n); 19 | void setBGR(const unsigned char* data,int n); 20 | void setBGRA(const unsigned char* data,int n); 21 | void setAlpha(const unsigned char* data,int n); 22 | void setLuminance(const ColorGradient& grad,int n); 23 | void setRGB(const ColorGradient& grad,int n); 24 | void setRGBA(const ColorGradient& grad,int n); 25 | void setAlpha(const ColorGradient& grad,int n); 26 | void setFilterLinear(); 27 | void setFilterNearest(); 28 | void setWrapClamp(); 29 | void setWrapRepeat(); 30 | void setCurrentGL(); 31 | 32 | GLTextureObject texObj; 33 | }; 34 | 35 | } //namespace GLDraw 36 | 37 | #endif 38 | 39 | -------------------------------------------------------------------------------- /GLdraw/GLTexture2D.h: -------------------------------------------------------------------------------- 1 | #ifndef GL_TEXTURE_2D_H 2 | #define GL_TEXTURE_2D_H 3 | 4 | #include "GLTextureObject.h" 5 | 6 | namespace GLDraw { 7 | 8 | /** @ingroup GLDraw 9 | * @brief 2D texture data for use in OpenGL. 10 | */ 11 | class GLTexture2D 12 | { 13 | public: 14 | GLTexture2D(); 15 | void setLuminance(const unsigned char* data,int m,int n); 16 | void setRGB(const unsigned char* data,int m,int n); 17 | void setRGBA(const unsigned char* data,int m,int n); 18 | void setBGR(const unsigned char* data,int m,int n); 19 | void setBGRA(const unsigned char* data,int m,int n); 20 | void setAlpha(const unsigned char* data,int m,int n); 21 | void setFilterLinear(); 22 | void setFilterNearest(); 23 | void setWrapClamp(); 24 | void setWrapRepeat(); 25 | void setCurrentGL(); 26 | 27 | GLTextureObject texObj; 28 | }; 29 | 30 | } //namespace GLDraw 31 | 32 | #endif 33 | 34 | -------------------------------------------------------------------------------- /GLdraw/GLTextureObject.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "GLTextureObject.h" 3 | #include "GL.h" 4 | #include 5 | using namespace std; 6 | 7 | using namespace GLDraw; 8 | 9 | GLTextureObject::GLTextureObject() 10 | {} 11 | 12 | GLTextureObject::GLTextureObject(const GLTextureObject& obj) 13 | { 14 | glName = obj.glName; 15 | } 16 | 17 | GLTextureObject::~GLTextureObject() 18 | { 19 | cleanup(); 20 | } 21 | 22 | bool GLTextureObject::isNull() const 23 | { 24 | return glName == NULL; 25 | } 26 | 27 | void GLTextureObject::generate() 28 | { 29 | if(glName == 0) { 30 | glName.reset(new unsigned int); 31 | glGenTextures(1, glName.get()); 32 | } 33 | else 34 | LOG4CXX_WARN(KrisLibrary::logger(),"Warning, GLTextureObject.generate() called on a non-null object"); 35 | } 36 | 37 | void GLTextureObject::cleanup() 38 | { 39 | 40 | if(glName && glName.use_count()==1) { 41 | glDeleteTextures(1, glName.get()); 42 | } 43 | glName = 0; 44 | } 45 | 46 | void GLTextureObject::bind(unsigned int target) const 47 | { 48 | if(glName) { 49 | glBindTexture(target,*glName); 50 | } 51 | } 52 | 53 | void GLTextureObject::unbind(unsigned int target) const 54 | { 55 | if(glName) { 56 | glBindTexture(target,0); 57 | } 58 | } 59 | -------------------------------------------------------------------------------- /GLdraw/GLTextureObject.h: -------------------------------------------------------------------------------- 1 | #ifndef GL_TEXTURE_OBJECT 2 | #define GL_TEXTURE_OBJECT 3 | 4 | #include 5 | 6 | namespace GLDraw { 7 | 8 | /** @ingroup GLDraw 9 | * @brief A GL texture object class. Simplifies allocating and cleaning up 10 | * texture objects. Usually you only need to interact with GLTexture[X]D 11 | * and the texture management is handled for you. 12 | */ 13 | class GLTextureObject 14 | { 15 | public: 16 | GLTextureObject(); 17 | GLTextureObject(const GLTextureObject&); 18 | ~GLTextureObject(); 19 | 20 | operator bool() const { return !isNull(); } 21 | void generate(); 22 | void cleanup(); 23 | void bind(unsigned int target) const; 24 | void unbind(unsigned int target) const; 25 | bool isNull() const; 26 | 27 | private: 28 | std::shared_ptr glName; 29 | }; 30 | 31 | } //namespace GLDraw 32 | 33 | #endif 34 | -------------------------------------------------------------------------------- /GLdraw/SphereWidget.h: -------------------------------------------------------------------------------- 1 | #ifndef GLDRAW_SPHERE_WIDGET_H 2 | #define GLDRAW_SPHERE_WIDGET_H 3 | 4 | #include "Widget.h" 5 | #include "TransformWidget.h" 6 | #include 7 | 8 | namespace GLDraw { 9 | 10 | class SphereWidget : public Widget 11 | { 12 | public: 13 | SphereWidget(const Sphere3D& s); 14 | void Get(Sphere3D& s) const; 15 | virtual ~SphereWidget() {} 16 | virtual bool Hover(int x,int y,Camera::Viewport& viewport,double& distance) override; 17 | virtual bool BeginDrag(int x,int y,Camera::Viewport& viewport,double& distance) override; 18 | virtual void Drag(int dx,int dy,Camera::Viewport& viewport) override; 19 | virtual void EndDrag() override; 20 | virtual void DrawGL(Camera::Viewport& viewport) override; 21 | virtual void SetHighlight(bool value) override; 22 | virtual void SetFocus(bool value) override; 23 | 24 | Real radius; 25 | TransformWidget transformWidget; // 5 | #include "GL.h" 6 | #include "drawextra.h" 7 | 8 | namespace GLDraw { 9 | 10 | inline void DrawGLTris(const Meshing::TriMesh& mesh) 11 | { 12 | glBegin(GL_TRIANGLES); 13 | for(size_t i=0;i 6 | #include 7 | #include "GL.h" 8 | 9 | namespace GLDraw { 10 | 11 | using namespace Math3D; 12 | 13 | void draw(const GeometricPrimitive2D& geom); 14 | void draw(const GeometricPrimitive3D& geom); 15 | void draw(const ConvexPolygon2D& geom); 16 | 17 | } //namespace GLDraw 18 | 19 | #endif 20 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | Copyright (c) 2013, the Trustees of Indiana University 2 | 3 | All rights reserved. 4 | 5 | Redistribution and use in source and binary forms, with or without modification, 6 | are permitted provided that the following conditions are met: 7 | 8 | * Redistributions of source code must retain the above copyright notice, this 9 | list of conditions and the following disclaimer. 10 | 11 | * Redistributions in binary form must reproduce the above copyright notice, this 12 | list of conditions and the following disclaimer in the documentation and/or 13 | other materials provided with the distribution. 14 | 15 | * Neither the name of Indiana University nor the names of its 16 | contributors may be used to endorse or promote products derived from 17 | this software without specific prior written permission. 18 | 19 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 20 | ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 21 | WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 22 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR 23 | ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 24 | (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 25 | LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON 26 | ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 27 | (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 28 | SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 29 | -------------------------------------------------------------------------------- /LICENSE.txt: -------------------------------------------------------------------------------- 1 | Copyright (c) 2013, the Trustees of Indiana University 2 | 3 | All rights reserved. 4 | 5 | Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: 6 | 7 | * Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. 8 | 9 | * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. 10 | 11 | * Neither the name of Indiana University nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. 12 | 13 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 14 | -------------------------------------------------------------------------------- /Timer.h: -------------------------------------------------------------------------------- 1 | #ifndef MY_TIMER_H 2 | #define MY_TIMER_H 3 | 4 | struct TimerImpl; 5 | 6 | class Timer 7 | { 8 | public: 9 | Timer(); 10 | Timer(const Timer& rhs); 11 | ~Timer(); 12 | const Timer& operator = (const Timer&); 13 | /// Resets the timer 14 | void Reset(); 15 | 16 | /// Returns elapsed time since constructor or last Reset() call, in milliseconds 17 | long long ElapsedTicks(); 18 | /// Returns elapsed time since constructor or last Reset() call, in seconds 19 | double ElapsedTime(); 20 | 21 | /// Returns elapsed time cached on prior ElapsedX call, in milliseconds 22 | long long LastElapsedTicks() const; 23 | /// Returns elapsed time cached on prior ElapsedX call, in seconds 24 | double LastElapsedTime() const; 25 | 26 | private: 27 | TimerImpl* impl; 28 | }; 29 | 30 | #endif 31 | -------------------------------------------------------------------------------- /camera/clip.h: -------------------------------------------------------------------------------- 1 | #ifndef CAMERA_CLIP_H 2 | #define CAMERA_CLIP_H 3 | 4 | // INCLUSION: The object is completely inside the volume. 5 | // (completely visible) 6 | #define INCLUSION -1 7 | // INTERSECT: The object intersects with one of more of the 8 | // volume's planes. (partially visible) 9 | #define INTERSECT 0 10 | // EXCLUSION: The object is completely outside the volume. 11 | // (invisible) 12 | #define EXCLUSION 1 13 | 14 | #include 15 | #include 16 | using namespace Math3D; 17 | 18 | //NOTE: the planes are defined so that normals point outward 19 | class ConvexVolume 20 | { 21 | public: 22 | int PointOverlap(const Vector3& pt) const; 23 | int AABBOverlap(const Vector3& bMin, const Vector3& bMax) const; 24 | int LineOverlap(const Line3D& pt, Real& tmin, Real& tmax) const; 25 | 26 | void Transform(const Matrix4& m); 27 | void SetTransform(const ConvexVolume&,const Matrix4& m); 28 | 29 | std::vector planes; 30 | }; 31 | 32 | #endif 33 | -------------------------------------------------------------------------------- /camera/frustum.h: -------------------------------------------------------------------------------- 1 | #ifndef CAMERA_FRUSTUM_H 2 | #define CAMERA_FRUSTUM_H 3 | 4 | #include "clip.h" 5 | #include "viewport.h" 6 | 7 | namespace Camera { 8 | 9 | struct Frustum : public ConvexVolume 10 | { 11 | enum { Right=0,Left=1,Top=2,Bottom=3,Front=4,Back=5 }; 12 | 13 | Frustum() 14 | { 15 | planes.resize(6); 16 | } 17 | 18 | void MakeFromViewport(const Viewport&); 19 | void MakeFromProjectionMatrix(const Matrix4&); 20 | void MakeFromViewMatrices(const Matrix4& modelview,const Matrix4& projection); 21 | }; 22 | 23 | } //namespace Camera 24 | 25 | #endif 26 | -------------------------------------------------------------------------------- /camera/transform.h: -------------------------------------------------------------------------------- 1 | #ifndef CAMERA_TRANSFORM_H 2 | #define CAMERA_TRANSFORM_H 3 | 4 | #include 5 | using namespace Math3D; 6 | 7 | //#warning "transform.h has been superceded by camera.h" 8 | 9 | void SetOrbitTransform(const Vector3& rot, const Vector3& target, float dist, RigidTransform& xform); 10 | void SetFreeTransform(const Vector3& pos, const Vector3& rot, RigidTransform& xform); 11 | void SetTargetTransform(const Vector3& pos, const Vector3& tgt, const Vector3& up, RigidTransform& xform); 12 | 13 | void GetOrbitTransform(const RigidTransform& xform, Vector3& rot, Vector3& target, float dist = One); 14 | void GetFreeTransform(const RigidTransform& xform, Vector3& pos, Vector3& rot); 15 | void GetTargetTransform(const RigidTransform& xform, Vector3& pos, Vector3& tgt, Vector3& up, float tgtDist = One); 16 | 17 | #endif 18 | -------------------------------------------------------------------------------- /errors.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "errors.h" 3 | #include 4 | 5 | #ifdef CYGWIN 6 | 7 | int counter=0; 8 | 9 | void Abort_Cygwin() 10 | { 11 | counter++; 12 | } 13 | 14 | void Abort() 15 | { 16 | LOG4CXX_FATAL(KrisLibrary::logger(),"Abort() called, aborting..."); 17 | LOG4CXX_FATAL(KrisLibrary::logger(),"To debug, re-run the program under gdb and enter `break Abort_Cygwin' before running"); 18 | Abort_Cygwin(); 19 | abort(); 20 | } 21 | 22 | #endif 23 | -------------------------------------------------------------------------------- /geometry/Arrangement1D.h: -------------------------------------------------------------------------------- 1 | #ifndef ARRANGEMENT_1D_H 2 | #define ARRANGEMENT_1D_H 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | 9 | namespace Geometry { 10 | 11 | using namespace Math; 12 | using namespace std; 13 | 14 | /** @ingroup Geometry 15 | * @brief An arrangement of 1-D intervals. Intervals identified by an 16 | * integer ID. 17 | */ 18 | class Arrangement1D 19 | { 20 | public: 21 | typedef pair Interval; 22 | typedef list IDList; 23 | struct LeftInterval { 24 | Interval interval; 25 | IDList pointIDs; //id list of left endpoint 26 | IDList intervalIDs; //id list of interval 27 | }; 28 | typedef map SortedIntervals; 29 | 30 | Arrangement1D(); 31 | void Insert(Real imin,Real imax,int id); 32 | void InsertUnique(Real imin,Real imax,int id); 33 | void GetIntervals(vector& intervals,vector& ids) const; 34 | void GetAllIntervals(vector& intervals,vector& ids) const; 35 | void GetOverlapIntervals(Real imin,Real imax,vector& intervals,vector& ids) const; 36 | 37 | //helpers 38 | SortedIntervals::iterator LocateInterval(Real x); 39 | SortedIntervals::const_iterator LocateInterval(Real x) const; 40 | void Split(SortedIntervals::iterator interval,Real x); 41 | 42 | SortedIntervals intervals; 43 | }; 44 | 45 | } //namespace Geometry 46 | 47 | #endif 48 | -------------------------------------------------------------------------------- /geometry/CollisionHeightmap.h: -------------------------------------------------------------------------------- 1 | #ifndef GEOMETRY_HEIGHTMAP_H 2 | #define GEOMETRY_HEIGHTMAP_H 3 | 4 | #include "GeometryType.h" 5 | #include "GeometryTypeImpl.h" 6 | 7 | namespace Geometry { 8 | 9 | using namespace std; 10 | 11 | class Collider3DHeightmap : public Collider3D 12 | { 13 | public: 14 | Collider3DHeightmap(shared_ptr data); 15 | virtual ~Collider3DHeightmap() {} 16 | virtual shared_ptr GetData() const override { return dynamic_pointer_cast(data); } 17 | virtual void Reset() override; 18 | virtual Box3D GetBB() const override; 19 | virtual RigidTransform GetTransform() const override; 20 | virtual void SetTransform(const RigidTransform& T) override; 21 | virtual bool Collides(Collider3D* geom,vector& elements1,vector& elements2,size_t maxcollisions=INT_MAX) override; 22 | virtual bool Contains(const Vector3& pt,bool& result) override; 23 | virtual bool WithinDistance(Collider3D* geom,Real d,vector& elements1,vector& elements2,size_t maxcollisions=INT_MAX) override; 24 | virtual bool RayCast(const Ray3D& r,Real margin,Real& distance,int& element) override; 25 | 26 | /// Returns index of grid cell closest to the projection of ptworld 27 | int PointToElement(const Vector3& ptworld) const; 28 | 29 | shared_ptr data; 30 | RigidTransform currentTransform; 31 | Real hmin,hmax; 32 | }; 33 | 34 | }//namespace Geometry 35 | 36 | #endif // GEOMETRY_HEIGHTMAP_H -------------------------------------------------------------------------------- /geometry/DCEL.h: -------------------------------------------------------------------------------- 1 | struct Vertex; 2 | struct HalfEdge; 3 | struct Face; 4 | 5 | struct Vertex 6 | { 7 | int data; 8 | HalfEdge* edge; //one edge with this vertex as head 9 | }; 10 | 11 | struct HalfEdge 12 | { 13 | Vertex* tail() const { return next->head; } 14 | 15 | int data; 16 | Vertex* head; 17 | Face* face; 18 | HalfEdge* next; 19 | HalfEdge* adj; 20 | }; 21 | 22 | struct Face 23 | { 24 | bool HasEdge(const Edge* e) const { 25 | HalfEdge* e = edge; 26 | do 27 | { 28 | if(e->adj->face == f) 29 | return true; 30 | e = e->next; 31 | } 32 | while(e != edge); 33 | return false; 34 | } 35 | HalfEdge AdjEdge(const Face* f) const { 36 | HalfEdge* e = edge; 37 | do 38 | { 39 | if(e->adj->face == f) 40 | return e; 41 | e = e->next; 42 | } 43 | while(e != edge); 44 | return NULL; 45 | } 46 | bool IsAdj(const Face* f) const { 47 | HalfEdge* e = AdjEdge(f); 48 | return (e != NULL); 49 | } 50 | 51 | int data; 52 | HalfEdge* edge; 53 | }; -------------------------------------------------------------------------------- /geometry/Fitting.h: -------------------------------------------------------------------------------- 1 | #ifndef GEOMETRY_FITTING_H 2 | #define GEOMETRY_FITTING_H 3 | 4 | #include 5 | #include 6 | 7 | namespace Math3D 8 | { 9 | struct Line2D; 10 | struct Line3D; 11 | struct Plane3D; 12 | struct Circle2D; 13 | } //namespace Math3D 14 | 15 | 16 | namespace Geometry { 17 | 18 | using namespace Math3D; 19 | 20 | Vector2 GetMean(const std::vector& pts); 21 | Vector3 GetMean(const std::vector& pts); 22 | void GetCovariance(const std::vector& pts,Matrix2& C); 23 | void GetCovariance(const std::vector& pts,Matrix3& C); 24 | 25 | bool FitGaussian(const std::vector& pts,Vector2& center,Matrix2& R,Vector2& axes); 26 | bool FitGaussian(const std::vector& pts,Vector3& center,Matrix3& R,Vector3& axes); 27 | 28 | bool FitLine(const std::vector& pts,Line2D& l); 29 | bool FitLine(const std::vector& pts,Line3D& l); 30 | bool FitPlane(const std::vector& pts,Plane3D& p); 31 | 32 | bool FitCircle(const std::vector& pts,Circle2D& c); 33 | //bool FitEllipse(const std::vector& pts,Ellipse2D& c); 34 | 35 | } //namespace Geometry 36 | 37 | #endif 38 | -------------------------------------------------------------------------------- /geometry/HACD_Lib/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | project(HACD_LIB CXX C) 2 | include(FindOpenMP) 3 | if(OPENMP_FOUND) 4 | set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}") 5 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") 6 | set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${OpenMP_EXE_LINKER_FLAGS}") 7 | endif() 8 | # set(LIB_TYPE "STATIC" CACHE STRING "STATIC, SHARED or MODULE?") 9 | set(HACD_LIB_INCLUDE ${CMAKE_CURRENT_SOURCE_DIR}/inc PARENT_SCOPE) 10 | # message("[HACD] \t LIB_TYPE " ${LIB_TYPE}) 11 | include_directories(${PROJECT_SOURCE_DIR}/inc) 12 | file(GLOB SRC_FILES ${PROJECT_SOURCE_DIR}/src/*.cpp) 13 | set(HACD_SRC_FILES ${SRC_FILES} PARENT_SCOPE) 14 | # add_library(HACD_LIB SHARED ${SRC_FILES}) 15 | 16 | # message("[HACD] \t -> CMAKE_INSTALL_PREFIX " ${CMAKE_INSTALL_PREFIX}) 17 | # install(TARGETS HACD_LIB DESTINATION bin) 18 | # install(FILES ${PROJECT_INC_FILES} DESTINATION include) 19 | # install(FILES ${PROJECT_INL_FILES} DESTINATION include) 20 | 21 | -------------------------------------------------------------------------------- /geometry/MonotoneChain.h: -------------------------------------------------------------------------------- 1 | #ifndef GEOMETRY_MONOTONE_CHAIN_H 2 | #define GEOMETRY_MONOTONE_CHAIN_H 3 | 4 | #include "primitives.h" 5 | #include 6 | 7 | namespace Geometry { 8 | 9 | using namespace Math; 10 | using namespace Math3D; 11 | 12 | /** @ingroup Geometry 13 | * @brief A polyline with vertices ordered in nondecreasing order. 14 | * 15 | * Need v[i].x <= v[i+1].x 16 | * if equality holds, then v[i].y < v[i+1].y. 17 | */ 18 | struct XMonotoneChain 19 | { 20 | Real eval(Real x) const; 21 | void upperEnvelope(const XMonotoneChain&); 22 | Real minimum(Real a,Real b,Real* x); 23 | bool isValid() const; 24 | static void SelfTest(); 25 | 26 | std::vector v; 27 | }; 28 | 29 | } //namespace Geometry 30 | 31 | #endif 32 | -------------------------------------------------------------------------------- /geometry/NeighborGraph.h: -------------------------------------------------------------------------------- 1 | #ifndef NEIGHBOR_GRAPH_H 2 | #define NEIGHBOR_GRAPH_H 3 | 4 | #include 5 | #include 6 | 7 | namespace Geometry { 8 | using namespace std; 9 | using namespace Math3D; 10 | 11 | ///Computes a graph where each node is an index of a point in the point cloud 12 | ///and each edge connects points within distance R (in Euclidean space) 13 | void NeighborGraph(const Meshing::PointCloud3D& pc,Real R,Graph::UndirectedGraph& G); 14 | 15 | ///Computes a graph where each node is an index of a point in the point cloud 16 | ///and each edge connects points within distance R (in Euclidean space) 17 | void NeighborGraph(const vector& pc,Real R,Graph::UndirectedGraph& G); 18 | 19 | ///Computes a graph where each node is an index of a point in the point cloud 20 | ///and each edge connects points (i,j) for which j is a k-nearest neighbor 21 | ///(in Euclidean space) 22 | void NearestNeighborGraph(const Meshing::PointCloud3D& pc,int k,Graph::Graph& G); 23 | 24 | ///Computes a graph where each node is an index of a point in the point cloud 25 | ///and each edge connects points (i,j) for which j is a k-nearest neighbor 26 | ///(in Euclidean space) 27 | void NearestNeighborGraph(const vector& pc,int k,Graph::Graph& G); 28 | 29 | } //Geometyr 30 | 31 | #endif 32 | -------------------------------------------------------------------------------- /geometry/PQP/Makefile: -------------------------------------------------------------------------------- 1 | CC = g++ 2 | 3 | CFLAGS = -g -O2 -fPIC -I. 4 | 5 | .SUFFIXES: .C .cpp 6 | 7 | OBJECTS = lib/PQP.o \ 8 | lib/BV.o \ 9 | lib/Build.o \ 10 | lib/TriDist.o 11 | 12 | CLEAN = $(OBJECTS) lib/libPQP.a include/*.h 13 | 14 | library: $(OBJECTS) 15 | /bin/rm -f lib/libPQP.a 16 | ar ruv lib/libPQP.a $(OBJECTS) 17 | cp src/PQP.h include/ 18 | cp src/PQP_Compile.h include/ 19 | cp src/PQP_Internal.h include/ 20 | cp src/BV.h include/ 21 | cp src/Tri.h include/ 22 | 23 | lib/BV.o: src/BV.cpp 24 | mkdir -p lib; 25 | $(CC) $(CFLAGS) -c src/BV.cpp -o lib/BV.o 26 | lib/PQP.o: src/PQP.cpp 27 | mkdir -p lib; 28 | $(CC) $(CFLAGS) -c src/PQP.cpp -o lib/PQP.o 29 | lib/Build.o: src/Build.cpp 30 | mkdir -p lib; 31 | $(CC) $(CFLAGS) -c src/Build.cpp -o lib/Build.o 32 | lib/TriDist.o: src/TriDist.cpp 33 | mkdir -p lib; 34 | $(CC) $(CFLAGS) -c src/TriDist.cpp -o lib/TriDist.o 35 | 36 | clean: 37 | /bin/rm -f $(CLEAN) 38 | -------------------------------------------------------------------------------- /geometry/PQP/PQP.dsw: -------------------------------------------------------------------------------- 1 | Microsoft Developer Studio Workspace File, Format Version 5.00 2 | # WARNING: DO NOT EDIT OR DELETE THIS WORKSPACE FILE! 3 | 4 | ############################################################################### 5 | 6 | Project: "PQP"=.\PQP.DSP - Package Owner=<4> 7 | 8 | Package=<5> 9 | {{{ 10 | }}} 11 | 12 | Package=<4> 13 | {{{ 14 | }}} 15 | 16 | ############################################################################### 17 | 18 | Global: 19 | 20 | Package=<5> 21 | {{{ 22 | }}} 23 | 24 | Package=<3> 25 | {{{ 26 | }}} 27 | 28 | ############################################################################### 29 | 30 | -------------------------------------------------------------------------------- /geometry/PQP/demos/Makefile: -------------------------------------------------------------------------------- 1 | all: 2 | cd sample; \ 3 | make 4 | cd spinning; \ 5 | make 6 | cd falling; \ 7 | make 8 | 9 | clean: 10 | cd sample; \ 11 | make clean 12 | cd spinning; \ 13 | make clean 14 | cd falling; \ 15 | make clean 16 | 17 | -------------------------------------------------------------------------------- /geometry/PQP/demos/demos.dsw: -------------------------------------------------------------------------------- 1 | Microsoft Developer Studio Workspace File, Format Version 5.00 2 | # WARNING: DO NOT EDIT OR DELETE THIS WORKSPACE FILE! 3 | 4 | ############################################################################### 5 | 6 | Project: "falling"=.\falling\falling.dsp - Package Owner=<4> 7 | 8 | Package=<5> 9 | {{{ 10 | }}} 11 | 12 | Package=<4> 13 | {{{ 14 | }}} 15 | 16 | ############################################################################### 17 | 18 | Project: "sample"=.\sample\sample.dsp - Package Owner=<4> 19 | 20 | Package=<5> 21 | {{{ 22 | }}} 23 | 24 | Package=<4> 25 | {{{ 26 | }}} 27 | 28 | ############################################################################### 29 | 30 | Project: "spinning"=.\spinning\spinning.dsp - Package Owner=<4> 31 | 32 | Package=<5> 33 | {{{ 34 | }}} 35 | 36 | Package=<4> 37 | {{{ 38 | }}} 39 | 40 | ############################################################################### 41 | 42 | Global: 43 | 44 | Package=<5> 45 | {{{ 46 | }}} 47 | 48 | Package=<3> 49 | {{{ 50 | }}} 51 | 52 | ############################################################################### 53 | 54 | -------------------------------------------------------------------------------- /geometry/PQP/demos/falling/Makefile: -------------------------------------------------------------------------------- 1 | # Must set these gl and glut locations to build 'falling' 2 | 3 | GL_INCPATH = -I/usr/local/include/ 4 | GL_LIBPATH = -L/usr/local/lib/ -L/usr/X11R6/lib/ 5 | GL_LIBS = -lglut -lGLU -lGL -lXext -lXmu -lXi -lX11 6 | 7 | .SUFFIXES: .cpp 8 | 9 | CC = g++ 10 | CFLAGS = -O2 -I. -I../../include $(GL_INCPATH) 11 | LDFLAGS = -L. -L../../lib $(GL_LIBPATH) 12 | LDLIBS = -lPQP -lm $(GL_LIBS) 13 | 14 | SRCS = main.cpp model.cpp 15 | 16 | OBJECTS = main.o model.o 17 | 18 | TARGET = falling 19 | 20 | CLEAN = $(OBJECTS) $(TARGET) 21 | 22 | .cpp.o: 23 | $(CC) ${CFLAGS} -c $< 24 | 25 | $(TARGET): $(OBJECTS) 26 | $(CC) $(CFLAGS) -o $(TARGET) $(OBJECTS) -L. $(LDFLAGS) $(LDLIBS) 27 | 28 | run: $(TARGET) 29 | $(TARGET) 30 | 31 | clean: 32 | /bin/rm -f $(CLEAN) 33 | 34 | -------------------------------------------------------------------------------- /geometry/PQP/demos/sample/Makefile: -------------------------------------------------------------------------------- 1 | CC = g++ 2 | 3 | CFLAGS = -O2 -I. -I../../include 4 | LDFLAGS = -L. -L../../lib 5 | LDLIBS = -lPQP -lm 6 | 7 | .SUFFIXES: .cpp 8 | 9 | SRCS = main.cpp 10 | 11 | OBJECTS = main.o 12 | 13 | TARGET = sample 14 | 15 | CLEAN = $(OBJECTS) $(TARGET) 16 | 17 | .cpp.o: 18 | $(CC) ${CFLAGS} -c $< 19 | 20 | $(TARGET): $(OBJECTS) 21 | $(CC) $(CFLAGS) -o $(TARGET) $(OBJECTS) -L. $(LDFLAGS) $(LDLIBS) 22 | 23 | run: $(TARGET) 24 | $(TARGET) 25 | 26 | clean: 27 | /bin/rm -f $(CLEAN) 28 | 29 | -------------------------------------------------------------------------------- /geometry/PQP/demos/sample/sample.plg: -------------------------------------------------------------------------------- 1 | --------------------Configuration: sample - Win32 Release-------------------- 2 | Begining build with project "C:\Win95\Desktop\PQP_v1.2.1\demos\sample\sample.dsp", at root. 3 | Active configuration is Win32 (x86) Console Application (based on Win32 (x86) Console Application) 4 | 5 | Project's tools are: 6 | "32-bit C/C++ Compiler for 80x86" with flags "/nologo /ML /W3 /GX /O2 /I "..\..\include" /D "WIN32" /D "NDEBUG" /D "_CONSOLE" /D "_MBCS" /Fp"Release/sample.pch" /YX /Fo"Release/" /Fd"Release/" /FD /c " 7 | "Win32 Resource Compiler" with flags "/l 0x409 /d "NDEBUG" " 8 | "Browser Database Maker" with flags "/nologo /o"./sample.bsc" " 9 | "COFF Linker for 80x86" with flags "pqp.lib kernel32.lib user32.lib gdi32.lib winspool.lib comdlg32.lib advapi32.lib shell32.lib ole32.lib oleaut32.lib uuid.lib odbc32.lib odbccp32.lib PQP.lib /nologo /subsystem:console /incremental:no /pdb:"./sample.pdb" /machine:I386 /out:"./sample.exe" /libpath:"..\..\lib" " 10 | "Custom Build" with flags "" 11 | "" with flags "" 12 | 13 | Creating temp file "C:\WIN95\TEMP\RSP6314.TMP" with contents 15 | Creating command line "link.exe @C:\WIN95\TEMP\RSP6314.TMP" 16 | Linking... 17 | 18 | 19 | 20 | sample.exe - 0 error(s), 0 warning(s) 21 | -------------------------------------------------------------------------------- /geometry/PQP/demos/spinning/Makefile: -------------------------------------------------------------------------------- 1 | # Must set these gl and glut locations to build 'spinning' 2 | 3 | CC = g++ 4 | 5 | GL_INCPATH = -I/usr/include/ 6 | GL_LIBPATH = -L/usr/lib/ -L/usr/X11R6/lib/ 7 | GL_LIBS = -lGLU -lGL -lXext -lXmu -lXi -lX11 -lglut 8 | 9 | .SUFFIXES: .cpp 10 | 11 | CC = g++ 12 | CFLAGS = -g -O2 -I. -I../../include $(GL_INCPATH) 13 | LDFLAGS = -L. -L../../lib -L/usr/lib/ -L/usr/X11R6/lib/ 14 | LDLIBS = -lPQP -lm $(GL_LIBS) 15 | 16 | OBJS = main.o model.o 17 | TARGET = spinning 18 | 19 | .cpp.o: 20 | $(CC) ${CFLAGS} -c $< 21 | 22 | $(TARGET): $(OBJS) 23 | $(CC) $(CFLAGS) $(OBJS) -o $(TARGET) $(LDFLAGS) $(LDLIBS) 24 | 25 | run: $(TARGET) 26 | $(TARGET) 27 | 28 | clean: 29 | rm -f *~ $(OBJS) $(TARGET) 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | -------------------------------------------------------------------------------- /geometry/PenetrationDepth.h: -------------------------------------------------------------------------------- 1 | #ifndef PENETRATION_DEPTH_H 2 | #define PENETRATION_DEPTH_H 3 | 4 | #include 5 | #include 6 | 7 | namespace Geometry { 8 | 9 | using namespace Math3D; 10 | 11 | /** @ingroup Geometry 12 | * @brief Uses a propagation method to calculate an approximate 13 | * penetration distance of mesh m1 inside m2. 14 | * 15 | * The method is similar to Heidelberger 2002. 16 | * The propagation is initialized using ComputeInitial() with the world-space 17 | * rigid-body transforms of the two meshes, and lists of overlapping triangles. 18 | * 19 | * Then, the approximate penetration depth is calculated using ComputeDepth(). 20 | * To re-initialize the computation use Reset(). 21 | */ 22 | class ApproximatePenetrationDepth 23 | { 24 | public: 25 | typedef Meshing::TriMeshWithTopology TriMeshWithTopology; 26 | typedef Meshing::TriMesh TriMesh; 27 | 28 | enum VertexClass { Unvisited=0, Fringe=1, Computed=2, Outside=3 }; 29 | 30 | ApproximatePenetrationDepth(const TriMeshWithTopology &m1, const TriMesh &m2); 31 | void Reset(); 32 | void ComputeInitial(const RigidTransform& f1,const RigidTransform& f2,const int tc1[], const int tc2[],int n); 33 | void ComputeDepth(); 34 | 35 | const TriMeshWithTopology &m1; 36 | const TriMesh &m2; 37 | std::vector vertexClass; 38 | std::vector depth; 39 | std::vector normal; 40 | std::vector fringe; 41 | Real maxDepth; 42 | Vector3 deepestPoint; 43 | Vector3 deepestNormal; 44 | }; 45 | 46 | } //namespace Math3D 47 | 48 | #endif 49 | -------------------------------------------------------------------------------- /geometry/UnboundedPolytope2D.h: -------------------------------------------------------------------------------- 1 | #ifndef GEOMETRY_UNBOUNDED_POLYTOPE_H 2 | #define GEOMETRY_UNBOUNDED_POLYTOPE_H 3 | 4 | #include 5 | #include "rayprimitives.h" 6 | #include 7 | 8 | namespace Geometry { 9 | 10 | using namespace Math3D; 11 | 12 | /** @ingroup Contact 13 | * @brief A representation of a possibly unbounded polytope in the 2d plane. 14 | * 15 | * Contains both a vertex/ray representation and a halfplane representation. 16 | */ 17 | struct UnboundedPolytope2D 18 | { 19 | /// Converts the vertex representation in vertices to planes 20 | void CalcPlanes(); 21 | /// Converts the plane representation to vertices 22 | void CalcVertices(); 23 | /// Returns true if the point is within the polytope 24 | bool Contains(const Vector2& x) const; 25 | /// Returns the orthogonal distance to the nearest plane (<0 means outside) 26 | Real Margin(const Vector2& x) const; 27 | /// Returns the closest point inside the polytope if one exists (<0 means 28 | /// the polytope was found to be empty) 29 | Real ClosestPoint(const Vector2& x,Vector2& cp) const; 30 | 31 | /// Vertex representation of the polygon 32 | std::vector vertices; 33 | 34 | /// Halfplane representation of the polygon. 35 | /// Normals point outward. 36 | std::vector planes; 37 | }; 38 | 39 | } //namespace Geometry 40 | 41 | #endif 42 | -------------------------------------------------------------------------------- /geometry/solid3/ChangeLog.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/krishauser/KrisLibrary/12cae4238edfaf21c6739c9af38601b42314e14a/geometry/solid3/ChangeLog.txt -------------------------------------------------------------------------------- /geometry/solid3/LICENSE_GPL.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/krishauser/KrisLibrary/12cae4238edfaf21c6739c9af38601b42314e14a/geometry/solid3/LICENSE_GPL.txt -------------------------------------------------------------------------------- /geometry/solid3/Makefile.am: -------------------------------------------------------------------------------- 1 | SUBDIRS = src include examples doc 2 | 3 | EXTRA_DIST = \ 4 | README.txt \ 5 | LICENSE_GPL.txt \ 6 | LICENSE_QPL.txt \ 7 | VisualC6.zip \ 8 | ChangeLog.txt 9 | -------------------------------------------------------------------------------- /geometry/solid3/doc/Makefile.am: -------------------------------------------------------------------------------- 1 | info_TEXINFOS = solid3.texi 2 | 3 | EXTRA_DIST = \ 4 | solid3.pdf \ 5 | solid3.html \ 6 | gpl.texi \ 7 | qpl.texi 8 | 9 | -------------------------------------------------------------------------------- /geometry/solid3/doc/solid3.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/krishauser/KrisLibrary/12cae4238edfaf21c6739c9af38601b42314e14a/geometry/solid3/doc/solid3.pdf -------------------------------------------------------------------------------- /geometry/solid3/doc/version.texi: -------------------------------------------------------------------------------- 1 | @set UPDATED Users October Oct 2 | @set UPDATED-MONTH October Oct 3 | @set EDITION 3.5 4 | @set VERSION 3.5 5 | -------------------------------------------------------------------------------- /geometry/solid3/examples/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | add_subdirectory(dynamics) 2 | 3 | add_executable(sample sample.cpp) 4 | add_dependencies(sample solid3) 5 | set_target_properties(sample PROPERTIES DEBUG_POSTFIX _d) 6 | target_link_libraries(sample solid3) 7 | 8 | set(DEPS dynamics solid3) 9 | 10 | if(GLUT_FOUND) 11 | 12 | include_directories( 13 | ${PROJECT_SOURCE_DIR}/examples/dynamics 14 | ${GLUT_INCLUDE_DIR} 15 | ${OPENGL_INCLUDE_DIR} 16 | ) 17 | 18 | foreach(EXE gldemo mnm physics) 19 | add_executable(${EXE} ${EXE}.cpp) 20 | add_dependencies(${EXE} ${DEPS}) 21 | set_target_properties(${EXE} PROPERTIES DEBUG_POSTFIX _d) 22 | target_link_libraries(${EXE} 23 | ${DEPS} 24 | ${GLUT_LIBRARIES} 25 | ${OPENGL_LIBRARIES} 26 | ) 27 | endforeach(EXE) 28 | 29 | endif(GLUT_FOUND) 30 | -------------------------------------------------------------------------------- /geometry/solid3/examples/Makefile.am: -------------------------------------------------------------------------------- 1 | SUBDIRS = dynamics 2 | 3 | noinst_PROGRAMS = sample gldemo physics mnm 4 | 5 | sample_SOURCES = sample.cpp 6 | gldemo_SOURCES = gldemo.cpp 7 | physics_SOURCES = physics.cpp 8 | mnm_SOURCES = mnm.cpp 9 | 10 | GLLIBS = -lglut -lGLU -lGL -L/usr/X11R6/lib -lXmu -lXi -lX11 11 | 12 | sample_LDADD = ../src/libsolid.la 13 | gldemo_LDADD = ../src/libsolid.la $(GLLIBS) 14 | physics_LDADD = dynamics/libdynamics.la ../src/libsolid.la $(GLLIBS) 15 | mnm_LDADD = dynamics/libdynamics.la ../src/libsolid.la $(GLLIBS) 16 | 17 | AM_CPPFLAGS = -I$(top_srcdir)/include -I$(top_srcdir)/examples/dynamics 18 | 19 | EXTRA_DIST = README.txt 20 | -------------------------------------------------------------------------------- /geometry/solid3/examples/dynamics/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | add_library(dynamics 2 | Dynamic.cpp 3 | Dynamic.h 4 | Kinetic.cpp 5 | Kinetic.h 6 | RigidBody.cpp 7 | RigidBody.h 8 | ) 9 | -------------------------------------------------------------------------------- /geometry/solid3/examples/dynamics/Makefile.am: -------------------------------------------------------------------------------- 1 | noinst_LTLIBRARIES = libdynamics.la 2 | 3 | libdynamics_la_SOURCES = \ 4 | Dynamic.cpp \ 5 | Dynamic.h \ 6 | Kinetic.cpp \ 7 | Kinetic.h \ 8 | RigidBody.cpp \ 9 | RigidBody.h 10 | 11 | AM_CPPFLAGS = -I$(top_srcdir)/include 12 | -------------------------------------------------------------------------------- /geometry/solid3/include/MT_Interval.h: -------------------------------------------------------------------------------- 1 | /* 2 | * SOLID - Software Library for Interference Detection 3 | * 4 | * Copyright (C) 2001-2003 Dtecta. All rights reserved. 5 | * 6 | * This library may be distributed under the terms of the Q Public License 7 | * (QPL) as defined by Trolltech AS of Norway and appearing in the file 8 | * LICENSE.QPL included in the packaging of this file. 9 | * 10 | * This library may be distributed and/or modified under the terms of the 11 | * GNU General Public License (GPL) version 2 as published by the Free Software 12 | * Foundation and appearing in the file LICENSE.GPL included in the 13 | * packaging of this file. 14 | * 15 | * This library is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE 16 | * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. 17 | * 18 | * Commercial use or any other use of this library not covered by either 19 | * the QPL or the GPL requires an additional license from Dtecta. 20 | * Please contact info@dtecta.com for enquiries about the terms of commercial 21 | * use of this library. 22 | */ 23 | 24 | #ifndef MT_INTERVAL_H 25 | #define MT_INTERVAL_H 26 | 27 | #include 28 | 29 | #include "MT_Scalar.h" 30 | 31 | typedef MT::Interval MT_Interval; 32 | 33 | #endif 34 | -------------------------------------------------------------------------------- /geometry/solid3/include/MT_Matrix3x3.h: -------------------------------------------------------------------------------- 1 | /* 2 | * SOLID - Software Library for Interference Detection 3 | * 4 | * Copyright (C) 2001-2003 Dtecta. All rights reserved. 5 | * 6 | * This library may be distributed under the terms of the Q Public License 7 | * (QPL) as defined by Trolltech AS of Norway and appearing in the file 8 | * LICENSE.QPL included in the packaging of this file. 9 | * 10 | * This library may be distributed and/or modified under the terms of the 11 | * GNU General Public License (GPL) version 2 as published by the Free Software 12 | * Foundation and appearing in the file LICENSE.GPL included in the 13 | * packaging of this file. 14 | * 15 | * This library is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE 16 | * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. 17 | * 18 | * Commercial use or any other use of this library not covered by either 19 | * the QPL or the GPL requires an additional license from Dtecta. 20 | * Please contact info@dtecta.com for enquiries about the terms of commercial 21 | * use of this library. 22 | */ 23 | 24 | #ifndef MT_MATRIX3X3_H 25 | #define MT_MATRIX3X3_H 26 | 27 | #include "MT_Scalar.h" 28 | #include 29 | 30 | typedef MT::Matrix3x3 MT_Matrix3x3; 31 | 32 | 33 | 34 | #endif 35 | -------------------------------------------------------------------------------- /geometry/solid3/include/MT_Point3.h: -------------------------------------------------------------------------------- 1 | /* 2 | * SOLID - Software Library for Interference Detection 3 | * 4 | * Copyright (C) 2001-2003 Dtecta. All rights reserved. 5 | * 6 | * This library may be distributed under the terms of the Q Public License 7 | * (QPL) as defined by Trolltech AS of Norway and appearing in the file 8 | * LICENSE.QPL included in the packaging of this file. 9 | * 10 | * This library may be distributed and/or modified under the terms of the 11 | * GNU General Public License (GPL) version 2 as published by the Free Software 12 | * Foundation and appearing in the file LICENSE.GPL included in the 13 | * packaging of this file. 14 | * 15 | * This library is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE 16 | * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. 17 | * 18 | * Commercial use or any other use of this library not covered by either 19 | * the QPL or the GPL requires an additional license from Dtecta. 20 | * Please contact info@dtecta.com for enquiries about the terms of commercial 21 | * use of this library. 22 | */ 23 | 24 | #ifndef MT_POINT3_H 25 | #define MT_POINT3_H 26 | 27 | #include "MT_Vector3.h" 28 | 29 | typedef MT_Vector3 MT_Point3; 30 | 31 | #endif 32 | -------------------------------------------------------------------------------- /geometry/solid3/include/MT_Quaternion.h: -------------------------------------------------------------------------------- 1 | /* 2 | * SOLID - Software Library for Interference Detection 3 | * 4 | * Copyright (C) 2001-2003 Dtecta. All rights reserved. 5 | * 6 | * This library may be distributed under the terms of the Q Public License 7 | * (QPL) as defined by Trolltech AS of Norway and appearing in the file 8 | * LICENSE.QPL included in the packaging of this file. 9 | * 10 | * This library may be distributed and/or modified under the terms of the 11 | * GNU General Public License (GPL) version 2 as published by the Free Software 12 | * Foundation and appearing in the file LICENSE.GPL included in the 13 | * packaging of this file. 14 | * 15 | * This library is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE 16 | * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. 17 | * 18 | * Commercial use or any other use of this library not covered by either 19 | * the QPL or the GPL requires an additional license from Dtecta. 20 | * Please contact info@dtecta.com for enquiries about the terms of commercial 21 | * use of this library. 22 | */ 23 | 24 | #ifndef MT_QUATERNION_H 25 | #define MT_QUATERNION_H 26 | 27 | #include "MT_Scalar.h" 28 | #include 29 | 30 | typedef MT::Quaternion MT_Quaternion; 31 | 32 | #endif 33 | 34 | 35 | 36 | -------------------------------------------------------------------------------- /geometry/solid3/include/MT_Transform.h: -------------------------------------------------------------------------------- 1 | /* 2 | * SOLID - Software Library for Interference Detection 3 | * 4 | * Copyright (C) 2001-2003 Dtecta. All rights reserved. 5 | * 6 | * This library may be distributed under the terms of the Q Public License 7 | * (QPL) as defined by Trolltech AS of Norway and appearing in the file 8 | * LICENSE.QPL included in the packaging of this file. 9 | * 10 | * This library may be distributed and/or modified under the terms of the 11 | * GNU General Public License (GPL) version 2 as published by the Free Software 12 | * Foundation and appearing in the file LICENSE.GPL included in the 13 | * packaging of this file. 14 | * 15 | * This library is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE 16 | * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. 17 | * 18 | * Commercial use or any other use of this library not covered by either 19 | * the QPL or the GPL requires an additional license from Dtecta. 20 | * Please contact info@dtecta.com for enquiries about the terms of commercial 21 | * use of this library. 22 | */ 23 | 24 | #ifndef MT_TRANSFORM_H 25 | #define MT_TRANSFORM_H 26 | 27 | #include "MT_Scalar.h" 28 | #include 29 | 30 | typedef MT::Matrix3x3 MT_Matrix3x3; 31 | typedef MT::Transform MT_Transform; 32 | 33 | #endif 34 | 35 | 36 | 37 | 38 | 39 | -------------------------------------------------------------------------------- /geometry/solid3/include/Makefile.am: -------------------------------------------------------------------------------- 1 | 2 | # The directory where the include files will be installed 3 | libsolidincludedir = $(includedir)/SOLID 4 | 5 | # Which header files to install 6 | libsolidinclude_HEADERS = \ 7 | SOLID.h \ 8 | SOLID_broad.h \ 9 | SOLID_types.h 10 | 11 | noinst_HEADERS = \ 12 | GEN_MinMax.h \ 13 | GEN_random.h \ 14 | MT_BBox.h \ 15 | MT_Interval.h \ 16 | MT_Matrix3x3.h \ 17 | MT_Point3.h \ 18 | MT_Quaternion.h \ 19 | MT_Scalar.h \ 20 | MT_ScalarTracer.h \ 21 | MT_Transform.h \ 22 | MT_Vector3.h \ 23 | MT/Interval.h \ 24 | MT/Matrix3x3.h \ 25 | MT/Quaternion.h \ 26 | MT/Transform.h \ 27 | MT/Tuple3.h \ 28 | MT/Tuple4.h \ 29 | MT/Vector3.h \ 30 | qhull/geom.h \ 31 | qhull/io.h \ 32 | qhull/mem.h \ 33 | qhull/merge.h \ 34 | qhull/poly.h \ 35 | qhull/qhull_a.h \ 36 | qhull/qhull.h \ 37 | qhull/qset.h \ 38 | qhull/stat.h \ 39 | qhull/user.h 40 | 41 | -------------------------------------------------------------------------------- /geometry/solid3/solid3-config.cmake.in: -------------------------------------------------------------------------------- 1 | set(SOLID3_VERSION "@VERSION@") 2 | set(SOLID3_VERSION_MAJOR "@VERSION_MAJOR@") 3 | set(SOLID3_VERSION_MINOR "@VERSION_MINOR@") 4 | set(SOLID3_VERSION_PATCH "@VERSION_PATCH@") 5 | 6 | @PACKAGE_INIT@ 7 | 8 | include("${CMAKE_CURRENT_LIST_DIR}/solid3-export.cmake") 9 | 10 | set(SOLID3_DEFINITIONS "") 11 | set(SOLID3_INCLUDE_DIRS "${PACKAGE_PREFIX_DIR}/include") 12 | set(SOLID3_LIBRARY_DIRS "${PACKAGE_PREFIX_DIR}/lib") 13 | set(SOLID3_LIBRARIES "solid3::solid3") 14 | -------------------------------------------------------------------------------- /geometry/solid3/src/Makefile.am: -------------------------------------------------------------------------------- 1 | SUBDIRS = broad convex complex qhull 2 | 3 | lib_LTLIBRARIES = libsolid.la 4 | 5 | libsolid_la_SOURCES = \ 6 | DT_AlgoTable.h \ 7 | DT_C-api.cpp \ 8 | DT_Encounter.h \ 9 | DT_Object.cpp \ 10 | DT_Object.h \ 11 | DT_RespTable.h \ 12 | DT_Scene.cpp \ 13 | DT_Scene.h \ 14 | DT_Encounter.cpp \ 15 | DT_Response.h \ 16 | DT_RespTable.cpp 17 | 18 | libsolid_la_LIBADD = \ 19 | broad/libbroad.la \ 20 | convex/libconvex.la \ 21 | complex/libcomplex.la \ 22 | qhull/libqhull.la 23 | 24 | AM_CPPFLAGS = -I$(top_srcdir)/include -I$(top_srcdir)/src/convex -I$(top_srcdir)/src/complex @DOUBLES_FLAG@ @TRACER_FLAG@ 25 | -------------------------------------------------------------------------------- /geometry/solid3/src/broad/Makefile.am: -------------------------------------------------------------------------------- 1 | noinst_LTLIBRARIES = libbroad.la 2 | 3 | libbroad_la_SOURCES = \ 4 | BP_C-api.cpp \ 5 | BP_Endpoint.h \ 6 | BP_EndpointList.cpp \ 7 | BP_EndpointList.h \ 8 | BP_Proxy.cpp \ 9 | BP_Proxy.h \ 10 | BP_ProxyList.h \ 11 | BP_Scene.cpp \ 12 | BP_Scene.h 13 | 14 | AM_CPPFLAGS = -I$(top_srcdir)/include 15 | 16 | -------------------------------------------------------------------------------- /geometry/solid3/src/complex/Makefile.am: -------------------------------------------------------------------------------- 1 | noinst_LTLIBRARIES = libcomplex.la 2 | 3 | libcomplex_la_SOURCES = \ 4 | DT_BBoxTree.cpp \ 5 | DT_BBoxTree.h \ 6 | DT_CBox.h \ 7 | DT_Complex.cpp \ 8 | DT_Complex.h 9 | 10 | AM_CPPFLAGS = -I$(top_srcdir)/include -I$(top_srcdir)/src -I$(top_srcdir)/src/convex @DOUBLES_FLAG@ @TRACER_FLAG@ 11 | -------------------------------------------------------------------------------- /geometry/solid3/src/convex/DT_Accuracy.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * SOLID - Software Library for Interference Detection 3 | * 4 | * Copyright (C) 2001-2003 Dtecta. All rights reserved. 5 | * 6 | * This library may be distributed under the terms of the Q Public License 7 | * (QPL) as defined by Trolltech AS of Norway and appearing in the file 8 | * LICENSE.QPL included in the packaging of this file. 9 | * 10 | * This library may be distributed and/or modified under the terms of the 11 | * GNU General Public License (GPL) version 2 as published by the Free Software 12 | * Foundation and appearing in the file LICENSE.GPL included in the 13 | * packaging of this file. 14 | * 15 | * This library is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE 16 | * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. 17 | * 18 | * Commercial use or any other use of this library not covered by either 19 | * the QPL or the GPL requires an additional license from Dtecta. 20 | * Please contact info@dtecta.com for enquiries about the terms of commercial 21 | * use of this library. 22 | */ 23 | 24 | #include "DT_Accuracy.h" 25 | 26 | static const MT_Scalar rel_error = MT_Scalar(1.0e-3); 27 | 28 | MT_Scalar DT_Accuracy::rel_error2 = rel_error * rel_error; 29 | MT_Scalar DT_Accuracy::depth_tolerance = MT_Scalar(1.0) + MT_Scalar(2.0) * rel_error; 30 | MT_Scalar DT_Accuracy::tol_error = MT_EPSILON; 31 | -------------------------------------------------------------------------------- /geometry/solid3/src/convex/DT_Cone.h: -------------------------------------------------------------------------------- 1 | /* 2 | * SOLID - Software Library for Interference Detection 3 | * 4 | * Copyright (C) 2001-2003 Dtecta. All rights reserved. 5 | * 6 | * This library may be distributed under the terms of the Q Public License 7 | * (QPL) as defined by Trolltech AS of Norway and appearing in the file 8 | * LICENSE.QPL included in the packaging of this file. 9 | * 10 | * This library may be distributed and/or modified under the terms of the 11 | * GNU General Public License (GPL) version 2 as published by the Free Software 12 | * Foundation and appearing in the file LICENSE.GPL included in the 13 | * packaging of this file. 14 | * 15 | * This library is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE 16 | * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. 17 | * 18 | * Commercial use or any other use of this library not covered by either 19 | * the QPL or the GPL requires an additional license from Dtecta. 20 | * Please contact info@dtecta.com for enquiries about the terms of commercial 21 | * use of this library. 22 | */ 23 | 24 | #ifndef DT_CONE_H 25 | #define DT_CONE_H 26 | 27 | #include "DT_Convex.h" 28 | 29 | class DT_Cone : public DT_Convex { 30 | public: 31 | DT_Cone(MT_Scalar r, MT_Scalar h) : 32 | bottomRadius(r), 33 | halfHeight(h * MT_Scalar(0.5)), 34 | sinAngle(r / MT_sqrt(r * r + h * h)) 35 | {} 36 | 37 | virtual MT_Point3 support(const MT_Vector3& v) const; 38 | 39 | protected: 40 | MT_Scalar bottomRadius; 41 | MT_Scalar halfHeight; 42 | MT_Scalar sinAngle; 43 | }; 44 | 45 | #endif 46 | -------------------------------------------------------------------------------- /geometry/solid3/src/convex/DT_Cylinder.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * SOLID - Software Library for Interference Detection 3 | * 4 | * Copyright (C) 2001-2003 Dtecta. All rights reserved. 5 | * 6 | * This library may be distributed under the terms of the Q Public License 7 | * (QPL) as defined by Trolltech AS of Norway and appearing in the file 8 | * LICENSE.QPL included in the packaging of this file. 9 | * 10 | * This library may be distributed and/or modified under the terms of the 11 | * GNU General Public License (GPL) version 2 as published by the Free Software 12 | * Foundation and appearing in the file LICENSE.GPL included in the 13 | * packaging of this file. 14 | * 15 | * This library is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE 16 | * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. 17 | * 18 | * Commercial use or any other use of this library not covered by either 19 | * the QPL or the GPL requires an additional license from Dtecta. 20 | * Please contact info@dtecta.com for enquiries about the terms of commercial 21 | * use of this library. 22 | */ 23 | 24 | #include "DT_Cylinder.h" 25 | 26 | MT_Point3 DT_Cylinder::support(const MT_Vector3& v) const 27 | { 28 | MT_Scalar s = MT_sqrt(v[0] * v[0] + v[2] * v[2]); 29 | if (s != MT_Scalar(0.0)) 30 | { 31 | MT_Scalar d = radius / s; 32 | return MT_Point3(v[0] * d, v[1] < 0.0 ? -halfHeight : halfHeight, v[2] * d); 33 | } 34 | else 35 | { 36 | return MT_Point3(radius, v[1] < 0.0 ? -halfHeight : halfHeight, MT_Scalar(0.0)); 37 | } 38 | } 39 | 40 | -------------------------------------------------------------------------------- /geometry/solid3/src/convex/DT_Cylinder.h: -------------------------------------------------------------------------------- 1 | /* 2 | * SOLID - Software Library for Interference Detection 3 | * 4 | * Copyright (C) 2001-2003 Dtecta. All rights reserved. 5 | * 6 | * This library may be distributed under the terms of the Q Public License 7 | * (QPL) as defined by Trolltech AS of Norway and appearing in the file 8 | * LICENSE.QPL included in the packaging of this file. 9 | * 10 | * This library may be distributed and/or modified under the terms of the 11 | * GNU General Public License (GPL) version 2 as published by the Free Software 12 | * Foundation and appearing in the file LICENSE.GPL included in the 13 | * packaging of this file. 14 | * 15 | * This library is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE 16 | * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. 17 | * 18 | * Commercial use or any other use of this library not covered by either 19 | * the QPL or the GPL requires an additional license from Dtecta. 20 | * Please contact info@dtecta.com for enquiries about the terms of commercial 21 | * use of this library. 22 | */ 23 | 24 | #ifndef DT_CYLINDER_H 25 | #define DT_CYLINDER_H 26 | 27 | #include "DT_Convex.h" 28 | 29 | class DT_Cylinder : public DT_Convex { 30 | public: 31 | DT_Cylinder(MT_Scalar r, MT_Scalar h) : 32 | radius(r), 33 | halfHeight(h * MT_Scalar(0.5)) {} 34 | 35 | virtual MT_Point3 support(const MT_Vector3& v) const; 36 | 37 | protected: 38 | MT_Scalar radius; 39 | MT_Scalar halfHeight; 40 | }; 41 | 42 | #endif 43 | -------------------------------------------------------------------------------- /geometry/solid3/src/convex/DT_IndexArray.h: -------------------------------------------------------------------------------- 1 | /* 2 | * SOLID - Software Library for Interference Detection 3 | * 4 | * Copyright (C) 2001-2003 Dtecta. All rights reserved. 5 | * 6 | * This library may be distributed under the terms of the Q Public License 7 | * (QPL) as defined by Trolltech AS of Norway and appearing in the file 8 | * LICENSE.QPL included in the packaging of this file. 9 | * 10 | * This library may be distributed and/or modified under the terms of the 11 | * GNU General Public License (GPL) version 2 as published by the Free Software 12 | * Foundation and appearing in the file LICENSE.GPL included in the 13 | * packaging of this file. 14 | * 15 | * This library is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE 16 | * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. 17 | * 18 | * Commercial use or any other use of this library not covered by either 19 | * the QPL or the GPL requires an additional license from Dtecta. 20 | * Please contact info@dtecta.com for enquiries about the terms of commercial 21 | * use of this library. 22 | */ 23 | 24 | #ifndef DT_INDEXARRAY_H 25 | #define DT_INDEXARRAY_H 26 | 27 | #include "SOLID_types.h" 28 | #include "DT_Array.h" 29 | 30 | typedef DT_Array DT_IndexArray; 31 | 32 | #endif 33 | 34 | -------------------------------------------------------------------------------- /geometry/solid3/src/convex/DT_LineSegment.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * SOLID - Software Library for Interference Detection 3 | * 4 | * Copyright (C) 2001-2003 Dtecta. All rights reserved. 5 | * 6 | * This library may be distributed under the terms of the Q Public License 7 | * (QPL) as defined by Trolltech AS of Norway and appearing in the file 8 | * LICENSE.QPL included in the packaging of this file. 9 | * 10 | * This library may be distributed and/or modified under the terms of the 11 | * GNU General Public License (GPL) version 2 as published by the Free Software 12 | * Foundation and appearing in the file LICENSE.GPL included in the 13 | * packaging of this file. 14 | * 15 | * This library is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE 16 | * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. 17 | * 18 | * Commercial use or any other use of this library not covered by either 19 | * the QPL or the GPL requires an additional license from Dtecta. 20 | * Please contact info@dtecta.com for enquiries about the terms of commercial 21 | * use of this library. 22 | */ 23 | 24 | #include "DT_LineSegment.h" 25 | 26 | MT_Scalar DT_LineSegment::supportH(const MT_Vector3& v) const 27 | { 28 | return GEN_max(v.dot(m_source), v.dot(m_target)); 29 | } 30 | 31 | MT_Point3 DT_LineSegment::support(const MT_Vector3& v) const 32 | { 33 | return v.dot(m_source) > v.dot(m_target) ? m_source : m_target; 34 | } 35 | 36 | 37 | -------------------------------------------------------------------------------- /geometry/solid3/src/convex/DT_PenDepth.h: -------------------------------------------------------------------------------- 1 | /* 2 | * SOLID - Software Library for Interference Detection 3 | * 4 | * Copyright (C) 2001-2003 Dtecta. All rights reserved. 5 | * 6 | * This library may be distributed under the terms of the Q Public License 7 | * (QPL) as defined by Trolltech AS of Norway and appearing in the file 8 | * LICENSE.QPL included in the packaging of this file. 9 | * 10 | * This library may be distributed and/or modified under the terms of the 11 | * GNU General Public License (GPL) version 2 as published by the Free Software 12 | * Foundation and appearing in the file LICENSE.GPL included in the 13 | * packaging of this file. 14 | * 15 | * This library is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE 16 | * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. 17 | * 18 | * Commercial use or any other use of this library not covered by either 19 | * the QPL or the GPL requires an additional license from Dtecta. 20 | * Please contact info@dtecta.com for enquiries about the terms of commercial 21 | * use of this library. 22 | */ 23 | 24 | #ifndef DT_PENDEPTH_H 25 | #define DT_PENDEPTH_H 26 | 27 | #include "MT_Vector3.h" 28 | #include "MT_Point3.h" 29 | 30 | class DT_GJK; 31 | class DT_Convex; 32 | 33 | bool penDepth(const DT_GJK& gjk, const DT_Convex& a, const DT_Convex& b, 34 | MT_Vector3& v, MT_Point3& pa, MT_Point3& pb); 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /geometry/solid3/src/convex/DT_Point.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * SOLID - Software Library for Interference Detection 3 | * 4 | * Copyright (C) 2001-2003 Dtecta. All rights reserved. 5 | * 6 | * This library may be distributed under the terms of the Q Public License 7 | * (QPL) as defined by Trolltech AS of Norway and appearing in the file 8 | * LICENSE.QPL included in the packaging of this file. 9 | * 10 | * This library may be distributed and/or modified under the terms of the 11 | * GNU General Public License (GPL) version 2 as published by the Free Software 12 | * Foundation and appearing in the file LICENSE.GPL included in the 13 | * packaging of this file. 14 | * 15 | * This library is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE 16 | * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. 17 | * 18 | * Commercial use or any other use of this library not covered by either 19 | * the QPL or the GPL requires an additional license from Dtecta. 20 | * Please contact info@dtecta.com for enquiries about the terms of commercial 21 | * use of this library. 22 | */ 23 | 24 | #include "DT_Point.h" 25 | 26 | MT_Scalar DT_Point::supportH(const MT_Vector3& v) const 27 | { 28 | return v.dot(m_point); 29 | } 30 | 31 | MT_Point3 DT_Point::support(const MT_Vector3& v) const 32 | { 33 | return m_point; 34 | } 35 | 36 | 37 | -------------------------------------------------------------------------------- /geometry/solid3/src/convex/DT_Point.h: -------------------------------------------------------------------------------- 1 | /* 2 | * SOLID - Software Library for Interference Detection 3 | * 4 | * Copyright (C) 2001-2003 Dtecta. All rights reserved. 5 | * 6 | * This library may be distributed under the terms of the Q Public License 7 | * (QPL) as defined by Trolltech AS of Norway and appearing in the file 8 | * LICENSE.QPL included in the packaging of this file. 9 | * 10 | * This library may be distributed and/or modified under the terms of the 11 | * GNU General Public License (GPL) version 2 as published by the Free Software 12 | * Foundation and appearing in the file LICENSE.GPL included in the 13 | * packaging of this file. 14 | * 15 | * This library is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE 16 | * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. 17 | * 18 | * Commercial use or any other use of this library not covered by either 19 | * the QPL or the GPL requires an additional license from Dtecta. 20 | * Please contact info@dtecta.com for enquiries about the terms of commercial 21 | * use of this library. 22 | */ 23 | 24 | #ifndef DT_POINT_H 25 | #define DT_POINT_H 26 | 27 | #include "DT_Convex.h" 28 | 29 | class DT_Point : public DT_Convex { 30 | public: 31 | DT_Point(const MT_Point3& point) : m_point(point) {} 32 | 33 | virtual MT_Scalar supportH(const MT_Vector3& v) const; 34 | virtual MT_Point3 support(const MT_Vector3& v) const; 35 | 36 | private: 37 | MT_Point3 m_point; 38 | }; 39 | 40 | #endif 41 | 42 | 43 | 44 | 45 | 46 | 47 | -------------------------------------------------------------------------------- /geometry/solid3/src/convex/Makefile.am: -------------------------------------------------------------------------------- 1 | noinst_LTLIBRARIES = libconvex.la 2 | 3 | libconvex_la_SOURCES = \ 4 | DT_Accuracy.cpp \ 5 | DT_Accuracy.h \ 6 | DT_Array.h \ 7 | DT_Box.cpp \ 8 | DT_Box.h \ 9 | DT_Cone.cpp \ 10 | DT_Cone.h \ 11 | DT_Convex.cpp \ 12 | DT_Convex.h \ 13 | DT_Cylinder.cpp \ 14 | DT_Cylinder.h \ 15 | DT_GJK.h \ 16 | DT_Hull.h \ 17 | DT_IndexArray.h \ 18 | DT_LineSegment.cpp \ 19 | DT_LineSegment.h \ 20 | DT_Minkowski.h \ 21 | DT_PenDepth.cpp \ 22 | DT_PenDepth.h \ 23 | DT_Point.cpp \ 24 | DT_Point.h \ 25 | DT_Polyhedron.cpp \ 26 | DT_Polyhedron.h \ 27 | DT_Polytope.cpp \ 28 | DT_Polytope.h \ 29 | DT_Shape.h \ 30 | DT_Sphere.cpp \ 31 | DT_Sphere.h \ 32 | DT_Transform.h \ 33 | DT_TriEdge.cpp \ 34 | DT_TriEdge.h \ 35 | DT_Triangle.cpp \ 36 | DT_Triangle.h \ 37 | DT_VertexBase.h 38 | 39 | AM_CPPFLAGS = -I$(top_srcdir)/include @DOUBLES_FLAG@ @TRACER_FLAG@ 40 | libconvex_la_LIBADD = @QHULL_LIBS@ -------------------------------------------------------------------------------- /geometry/solid3/src/qhull/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | project(QHULL_LIB CXX C) 2 | add_library(qhull OBJECT 3 | geom.c 4 | geom.h 5 | geom2.c 6 | global.c 7 | io.c 8 | io.h 9 | mem.c 10 | mem.h 11 | merge.c 12 | merge.h 13 | poly.c 14 | poly.h 15 | poly2.c 16 | qhull.c 17 | qhull.h 18 | qhull_a.h 19 | qset.c 20 | qset.h 21 | stat.c 22 | stat.h 23 | user.c 24 | user.h 25 | ) 26 | 27 | file(GLOB SRC_FILES ${PROJECT_SOURCE_DIR}/*.c ${PROJECT_SOURCE_DIR}/*.h) 28 | set(QHULL_INCLUDE_DIR ${PROJECT_SOURCE_DIR} PARENT_SCOPE) 29 | 30 | set(QHULL_SRC_FILES 31 | ${SRC_FILES} 32 | PARENT_SCOPE 33 | ) 34 | 35 | 36 | 37 | -------------------------------------------------------------------------------- /geometry/solid3/src/qhull/Makefile.am: -------------------------------------------------------------------------------- 1 | noinst_LTLIBRARIES = libqhull.la 2 | 3 | libqhull_la_SOURCES = \ 4 | user.c \ 5 | global.c \ 6 | stat.c \ 7 | io.c \ 8 | geom2.c \ 9 | poly2.c \ 10 | merge.c \ 11 | qhull.c \ 12 | geom.c \ 13 | poly.c \ 14 | qset.c \ 15 | mem.c \ 16 | geom.h \ 17 | io.h \ 18 | mem.h \ 19 | merge.h \ 20 | poly.h \ 21 | qhull_a.h \ 22 | qhull.h \ 23 | qset.h \ 24 | stat.h \ 25 | user.h 26 | 27 | AM_CFLAGS = -fno-strict-aliasing 28 | 29 | 30 | 31 | -------------------------------------------------------------------------------- /geometry/solid3/src/qhull/index.htm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/krishauser/KrisLibrary/12cae4238edfaf21c6739c9af38601b42314e14a/geometry/solid3/src/qhull/index.htm -------------------------------------------------------------------------------- /geometry/solid3/src/qhull/qh-geom.htm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/krishauser/KrisLibrary/12cae4238edfaf21c6739c9af38601b42314e14a/geometry/solid3/src/qhull/qh-geom.htm -------------------------------------------------------------------------------- /geometry/solid3/src/qhull/qh-globa.htm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/krishauser/KrisLibrary/12cae4238edfaf21c6739c9af38601b42314e14a/geometry/solid3/src/qhull/qh-globa.htm -------------------------------------------------------------------------------- /geometry/solid3/src/qhull/qh-io.htm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/krishauser/KrisLibrary/12cae4238edfaf21c6739c9af38601b42314e14a/geometry/solid3/src/qhull/qh-io.htm -------------------------------------------------------------------------------- /geometry/solid3/src/qhull/qh-mem.htm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/krishauser/KrisLibrary/12cae4238edfaf21c6739c9af38601b42314e14a/geometry/solid3/src/qhull/qh-mem.htm -------------------------------------------------------------------------------- /geometry/solid3/src/qhull/qh-merge.htm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/krishauser/KrisLibrary/12cae4238edfaf21c6739c9af38601b42314e14a/geometry/solid3/src/qhull/qh-merge.htm -------------------------------------------------------------------------------- /geometry/solid3/src/qhull/qh-poly.htm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/krishauser/KrisLibrary/12cae4238edfaf21c6739c9af38601b42314e14a/geometry/solid3/src/qhull/qh-poly.htm -------------------------------------------------------------------------------- /geometry/solid3/src/qhull/qh-qhull.htm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/krishauser/KrisLibrary/12cae4238edfaf21c6739c9af38601b42314e14a/geometry/solid3/src/qhull/qh-qhull.htm -------------------------------------------------------------------------------- /geometry/solid3/src/qhull/qh-set.htm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/krishauser/KrisLibrary/12cae4238edfaf21c6739c9af38601b42314e14a/geometry/solid3/src/qhull/qh-set.htm -------------------------------------------------------------------------------- /geometry/solid3/src/qhull/qh-stat.htm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/krishauser/KrisLibrary/12cae4238edfaf21c6739c9af38601b42314e14a/geometry/solid3/src/qhull/qh-stat.htm -------------------------------------------------------------------------------- /geometry/solid3/src/qhull/qh-user.htm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/krishauser/KrisLibrary/12cae4238edfaf21c6739c9af38601b42314e14a/geometry/solid3/src/qhull/qh-user.htm -------------------------------------------------------------------------------- /graph/ConnectedComponents.h: -------------------------------------------------------------------------------- 1 | #ifndef GRAPH_CONNECTED_COMPONENTS_H 2 | #define GRAPH_CONNECTED_COMPONENTS_H 3 | 4 | #include "UndirectedGraph.h" 5 | #include 6 | 7 | namespace Graph { 8 | 9 | class ConnectedComponents 10 | { 11 | public: 12 | ConnectedComponents() {} 13 | template 14 | void Compute(const UndirectedGraph& G) { 15 | sets.Initialize(G.nodes.size()); 16 | for(size_t i=0;i& reps) const { sets.GetRoots(reps); } 31 | size_t NumComponents() const { return sets.CountSets(); } 32 | void EnumerateComponent(int node,std::vector& items) const { return sets.EnumerateSet(node,items); } 33 | 34 | UnionFind sets; 35 | }; 36 | 37 | } //namespace Graph 38 | 39 | #endif 40 | -------------------------------------------------------------------------------- /graph/Node.h: -------------------------------------------------------------------------------- 1 | #ifndef GRAPH_NODE_H 2 | #define GRAPH_NODE_H 3 | 4 | namespace Graph { 5 | 6 | enum Color { White, Grey, Black }; 7 | 8 | } //namespace Graph 9 | 10 | #endif 11 | -------------------------------------------------------------------------------- /image/gdi.h: -------------------------------------------------------------------------------- 1 | #ifndef IMAGE_GDI_H 2 | #define IMAGE_GDI_H 3 | 4 | #ifdef NOMINMAX 5 | #undef NOMINMAX 6 | #endif // NOMINMAX 7 | #include 8 | #include 9 | #include "image.h" 10 | 11 | //fmtOut gets the closest possible GDI+ format to be written to the image 12 | Image::PixelFormat GdiToImagePixelFormat(Gdiplus::PixelFormat fmt, Gdiplus::PixelFormat& fmtOut); 13 | Gdiplus::PixelFormat ImageGdiPixelFormat(Image::PixelFormat fmt); 14 | void GdiBitmapToImage(Gdiplus::Bitmap& bit, Image& img); 15 | Gdiplus::Bitmap* ImageToGdiBitmap(const Image& img); 16 | 17 | bool ImportImageGDIPlus(const char* fn, Image& img); 18 | bool ExportImageGDIPlus(const char* fn, const Image& img); 19 | 20 | #endif -------------------------------------------------------------------------------- /image/io.h: -------------------------------------------------------------------------------- 1 | #ifndef IMAGE_IMPORT_EXPORT_H 2 | #define IMAGE_IMPORT_EXPORT_H 3 | 4 | #include "image.h" 5 | 6 | bool ImportImage(const char* fn, Image& img); 7 | bool ImportImagePPM(const char* fn, Image& img); 8 | bool ImportImageBMP(const char* fn, Image& img); 9 | bool ImportImageTGA(const char* fn, Image& img); 10 | bool ImportImageGDIPlus(const char* fn, Image& img); 11 | ///Returns a semicolon-separated list of supported image types. 12 | ///This may not be exhaustive. 13 | const char* ImageImportTypes(); 14 | 15 | bool ExportImage(const char* fn, const Image& img); 16 | bool ExportImagePPM(const char* fn, const Image& img); 17 | bool ExportImageGDIPlus(const char* fn, const Image& img); 18 | ///Returns a semicolon-separated list of supported image types. 19 | ///This may not be exhaustive. 20 | const char* ImageExportTypes(); 21 | 22 | #endif 23 | -------------------------------------------------------------------------------- /image/ppm.h: -------------------------------------------------------------------------------- 1 | #ifndef IMAGE_PPM_H 2 | #define IMAGE_PPM_H 3 | 4 | #include "image.h" 5 | 6 | bool WritePPM_RGB_ASCII(unsigned char image[],int m,int n,const char* file); 7 | bool WritePPM_Grayscale_ASCII(unsigned char image[],int m,int n,const char* file); 8 | bool WritePPM_RGB_Binary(unsigned char image[],int m,int n,const char* file); 9 | bool WritePPM_Grayscale_Binary(unsigned char image[],int m,int n,const char* file); 10 | 11 | bool ReadPPM_RGB(unsigned char** image,int* m,int* n,const char* file); 12 | bool ReadPPM_Grayscale(unsigned char** image,int* m,int* n,const char* file); 13 | 14 | bool ExportImagePPM(const char* fn, Image& img,bool binary); 15 | bool ExportImagePPM(const char* fn, Image& img); 16 | 17 | #endif 18 | -------------------------------------------------------------------------------- /image/textureops.h: -------------------------------------------------------------------------------- 1 | #ifdef WIN32 2 | #define WIN32_LEAN_AND_MEAN 3 | #include 4 | #endif //WIN32 5 | #include "image.h" 6 | 7 | #ifdef WIN32 8 | bool LoadImageFromBitmap(HDC hdc, HBITMAP hbit, Image& image); 9 | #endif //WIN32 10 | bool IsSquare(const Image& tex); 11 | void StretchSquare(Image& tex); 12 | void ExpandSquare(Image& tex); 13 | 14 | -------------------------------------------------------------------------------- /math/ASCIIShade.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_ASCII_SHADE_H 2 | #define MATH_ASCII_SHADE_H 3 | 4 | #include "vector.h" 5 | #include "matrix.h" 6 | 7 | namespace Math { 8 | 9 | char ASCIIShade(double x); 10 | void OutputASCIIShade(std::ostream& out,double x); 11 | void OutputASCIIShade(std::ostream& out,const fVector& x,float scale=0); 12 | void OutputASCIIShade(std::ostream& out,const fMatrix& A,float scale=0,int indent=0); 13 | void OutputASCIIShade(std::ostream& out,const dVector& x,double scale=0); 14 | void OutputASCIIShade(std::ostream& out,const dMatrix& A,double scale=0,int indent=0); 15 | 16 | } //namespace Math 17 | 18 | #endif 19 | -------------------------------------------------------------------------------- /math/AngleSet.cpp: -------------------------------------------------------------------------------- 1 | #include "AngleSet.h" 2 | using namespace Math; 3 | using namespace std; 4 | 5 | void AngleSet::Intersect(const vector& s) 6 | { 7 | AngleSet newIntervals; 8 | AngleInterval temp; 9 | for(size_t i=0; i 6 | 7 | namespace Math { 8 | 9 | /** @ingroup Math 10 | * @brief A set of AngleIntervals. 11 | */ 12 | struct AngleSet : public std::vector 13 | { 14 | typedef std::vector BaseT; 15 | 16 | inline void SetCircle() { resize(1); (*this)[0].setCircle(); } 17 | inline void SetEmpty() { clear(); } 18 | void Union(const BaseT&); 19 | void Intersect(const BaseT&); 20 | void Subtract(const BaseT&); 21 | void Union(const AngleInterval&); 22 | void Intersect(const AngleInterval&); 23 | void Subtract(const AngleInterval&); 24 | }; 25 | 26 | } //namespace Math 27 | 28 | #endif 29 | -------------------------------------------------------------------------------- /math/BlockPrinter.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_BLOCK_PRINTER_H 2 | #define MATH_BLOCK_PRINTER_H 3 | 4 | #include "BlockVector.h" 5 | #include "BlockTridiagonalMatrix.h" 6 | 7 | namespace Math { 8 | 9 | struct BlockPrinter 10 | { 11 | BlockPrinter(const BlockVector& v); 12 | BlockPrinter(const BlockTridiagonalMatrix& m); 13 | void Print(std::ostream& out) const; 14 | 15 | const BlockVector* v; 16 | const BlockTridiagonalMatrix* m; 17 | char delim,bracket; 18 | }; 19 | 20 | std::ostream& operator <<(std::ostream& out,const BlockPrinter& bp); 21 | 22 | } //namespace Math 23 | 24 | #endif 25 | -------------------------------------------------------------------------------- /math/CholeskyDecomposition.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_CHOLESKY_DECOMPOSITION_H 2 | #define MATH_CHOLESKY_DECOMPOSITION_H 3 | 4 | #include "matrix.h" 5 | 6 | namespace Math { 7 | 8 | /** @ingroup Math 9 | * @brief Performs the Cholesky decomposition. 10 | * 11 | * Decomposes the positive semi-definite matrix A to LL^t. 12 | */ 13 | template 14 | class CholeskyDecomposition 15 | { 16 | public: 17 | typedef MatrixTemplate MatrixT; 18 | typedef VectorTemplate VectorT; 19 | 20 | CholeskyDecomposition(); 21 | CholeskyDecomposition(const MatrixT& A); 22 | CholeskyDecomposition(const MatrixT& A,MatrixT& L); 23 | 24 | void setDestination(MatrixT& L); 25 | bool set(const MatrixT& A); 26 | bool setPerturbed(const MatrixT& A,T& lambda); 27 | void backSub(const VectorT& b, VectorT& x) const; 28 | void LBackSub(const VectorT& b, VectorT& x) const; 29 | void LTBackSub(const VectorT& b, VectorT& x) const; 30 | void backSub(const MatrixT& B, MatrixT& X) const; 31 | void getInverse(MatrixT& Ainv) const; 32 | 33 | /// Update the cholesky decomposition for A + xx^t 34 | void update(const VectorT& x); 35 | /// "Downdate" the cholesky decomposition for A - xx^t (on failure, L is undefined) 36 | bool downdate(const VectorT& x); 37 | 38 | MatrixT L; 39 | T zeroEpsilon; 40 | }; 41 | 42 | } 43 | #endif 44 | -------------------------------------------------------------------------------- /math/Conditioner.cpp: -------------------------------------------------------------------------------- 1 | #include "Conditioner.h" 2 | #include 3 | using namespace Math; 4 | using namespace std; 5 | 6 | Conditioner_SymmDiag::Conditioner_SymmDiag(Matrix& A,Vector& b,Method m) 7 | :MatrixEquation(A,b) 8 | { 9 | CalculateS(m); 10 | if(S.n!=0) { 11 | //S.preMultiply(A,A); 12 | //S.postMultiply(A,A); 13 | //S.mulVector(b,b); 14 | S.preMultiplyInverse(A,A); 15 | S.postMultiplyInverse(A,A); 16 | S.mulInverse(b,b); 17 | } 18 | } 19 | 20 | void Conditioner_SymmDiag::Post(Vector& x) const 21 | { 22 | if(S.n!=0) { 23 | //S.mulVector(x,x); 24 | S.mulInverse(x,x); 25 | } 26 | } 27 | 28 | void Conditioner_SymmDiag::CalculateS(Method m) 29 | { 30 | switch(m) { 31 | case None: break; 32 | case NormalizeDiagonal: CalculateS_NormalizeDiagonal(); break; 33 | } 34 | } 35 | 36 | void Conditioner_SymmDiag::CalculateS_NormalizeDiagonal() 37 | { 38 | assert(A.m == A.n); 39 | S.resize(A.n); 40 | for(int i=0;i 15 | int OrthonormalBasis(const VectorTemplate* x, VectorTemplate* basis, int n); 16 | 17 | ///Same as above, but does not normalize 18 | template 19 | int OrthogonalBasis(const VectorTemplate* x, VectorTemplate* basis, int n); 20 | 21 | ///orthogonalizes a vector w.r.t the orthogonal basis of n vectors 22 | template 23 | void Orthogonalize(VectorTemplate& x,const VectorTemplate* basis, int n); 24 | 25 | /*@}*/ 26 | } //namespace Math 27 | 28 | #endif 29 | -------------------------------------------------------------------------------- /math/Householder.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_HOUSEHOLDER_H 2 | #define MATH_HOUSEHOLDER_H 3 | 4 | #include "VectorTemplate.h" 5 | #include "MatrixTemplate.h" 6 | 7 | /** @file Householder.h 8 | * @ingroup Math 9 | * @brief Functions for householder transformations. 10 | */ 11 | 12 | namespace Math { 13 | 14 | /** @addtogroup Math */ 15 | /*@{*/ 16 | 17 | /** Replace v[0:n-1] with a householder vector (v[0:n-1]) and 18 | coefficient tau that annihilate v[1:n-1]. Tau is returned */ 19 | template 20 | T HouseholderTransform(VectorTemplate& v); 21 | 22 | /** Applies a householder transformation v,tau to matrix A */ 23 | template 24 | void HouseholderPreMultiply(T tau, const VectorTemplate& v, MatrixTemplate& A); 25 | 26 | /** Applies a householder transformation v,tau to matrix m from the 27 | right hand side in order to zero out rows */ 28 | template 29 | void HouseholderPostMultiply(T tau, const VectorTemplate& v, MatrixTemplate& A); 30 | 31 | /** Applies a householder transformation tau,v to vector w */ 32 | template 33 | void HouseholderApply(T tau, const VectorTemplate& v, VectorTemplate& w); 34 | 35 | /** Applies a householder transformation v,tau to a matrix being 36 | built up from the identity matrix, using the first column of A as 37 | a householder vector */ 38 | template 39 | void HouseholderHM1(T tau, MatrixTemplate& A); 40 | 41 | /*@}*/ 42 | } //namespace Math 43 | 44 | #endif 45 | -------------------------------------------------------------------------------- /math/IntervalSet.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_INTERVAL_SET_H 2 | #define MATH_INTERVAL_SET_H 3 | 4 | #include "Interval.h" 5 | #include 6 | 7 | namespace Math { 8 | 9 | struct OpenIntervalSet : public std::vector 10 | { 11 | typedef std::vector BaseT; 12 | typedef std::vector ClosedBaseT; 13 | 14 | inline void SetFull() { resize(1); (*this)[0].setFull(); } 15 | inline void SetEmpty() { clear(); } 16 | void Union(const BaseT&); 17 | void Intersect(const BaseT&); 18 | void Subtract(const ClosedBaseT&); 19 | void Union(const OpenInterval&); 20 | void Intersect(const OpenInterval&); 21 | void Subtract(const ClosedInterval&); 22 | }; 23 | 24 | struct ClosedIntervalSet : public std::vector 25 | { 26 | typedef std::vector BaseT; 27 | typedef std::vector OpenBaseT; 28 | 29 | inline void SetFull() { resize(1); (*this)[0].setFull(); } 30 | inline void SetEmpty() { clear(); } 31 | void Union(const BaseT&); 32 | void Intersect(const BaseT&); 33 | void Subtract(const OpenBaseT&); 34 | void Union(const ClosedInterval&); 35 | void Intersect(const ClosedInterval&); 36 | void Subtract(const OpenInterval&); 37 | }; 38 | 39 | } //namespace Math 40 | 41 | #endif 42 | -------------------------------------------------------------------------------- /math/LUDecomposition.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_LU_DECOMPOSITION_H 2 | #define MATH_LU_DECOMPOSITION_H 3 | 4 | #include "MatrixTemplate.h" 5 | #include 6 | 7 | namespace Math { 8 | 9 | /** @ingroup Math 10 | * @brief Forms the LU decomposition A=PLU 11 | * 12 | * L is stored in the lower sub-diagonal triangle of LU, 13 | * and formed to have ones on the diagonal. 14 | * U is stored in the upper triangle of LU. 15 | * P^-1 is stored as a permutation vector 16 | */ 17 | template 18 | class LUDecomposition 19 | { 20 | public: 21 | typedef MatrixTemplate MatrixT; 22 | typedef VectorTemplate VectorT; 23 | 24 | LUDecomposition(); 25 | LUDecomposition(const MatrixT& A); 26 | 27 | bool set(const MatrixT& A); 28 | void backSub(const VectorT& b, VectorT& x) const; 29 | void PBackSub(const VectorT& b, VectorT& x) const; 30 | void LBackSub(const VectorT& b, VectorT& x) const; 31 | void UBackSub(const VectorT& b, VectorT& x) const; 32 | void getInverse(MatrixT& Ainv) const; 33 | 34 | void getL(MatrixT& L) const; 35 | void getU(MatrixT& U) const; 36 | 37 | MatrixT LU; 38 | std::vector P; 39 | T zeroTolerance; 40 | }; 41 | 42 | } 43 | #endif 44 | -------------------------------------------------------------------------------- /math/LinearlyDependent.cpp: -------------------------------------------------------------------------------- 1 | #include "LinearlyDependent.h" 2 | 3 | namespace Math { 4 | 5 | template 6 | bool LinearlyDependent_Robust(const VectorTemplate& a, const VectorTemplate& b, T& c, bool& cb, T eps) 7 | { 8 | assert(a.n == b.n); 9 | T aDotB = a.dot(b); 10 | T aNorm2 = a.normSquared(); 11 | if(aNorm2 > Abs(aDotB)) { 12 | cb = false; 13 | c = aDotB/aNorm2; 14 | T aNorm = Sqrt(aNorm2); 15 | T relEps = eps*aNorm; 16 | for(int i=0;i 22 | bool LinearlyDependent_Robust(const VectorTemplate& a, const VectorTemplate& b, T& c, bool& cb, T eps = Epsilon); 23 | 24 | /** @ingroup Math 25 | * @brief A matrix version of the function above. 26 | * 27 | * @return A vector c s.t. A*c = 0. All coefficients |ci| <= 1 28 | * At least one ci = 1. 29 | */ 30 | template 31 | bool LinearlyDependent_Robust(const MatrixTemplate& A, VectorTemplate& c, T eps = Epsilon); 32 | 33 | 34 | } //namespace Math 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /math/MatrixEquationPrinter.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_MATRIX_EQUATION_PRINTER_H 2 | #define MATH_MATRIX_EQUATION_PRINTER_H 3 | 4 | #include "matrix.h" 5 | #include 6 | 7 | namespace Math 8 | { 9 | 10 | struct EquationTerm 11 | { 12 | EquationTerm(); 13 | int Height() const; 14 | int Width() const; 15 | void PrintLine(int line,std::ostream& out) const; 16 | 17 | const Matrix* matrix; 18 | const Vector* vector; 19 | const char* text; 20 | Real scalar; 21 | bool transpose; 22 | bool ASCIIshade; 23 | }; 24 | 25 | class MatrixEquationPrinter 26 | { 27 | public: 28 | void PushMatrix(const Matrix&); 29 | void PushMatrixTranspose(const Matrix&); 30 | void PushVector(const Vector&); 31 | void PushText(const char*); 32 | void PushScalar(Real); 33 | inline void PushAdd() { PushText("+"); } 34 | inline void PushSub() { PushText("-"); } 35 | inline void PushTimes() { PushText("*"); } 36 | inline void PushDot() { PushText("."); } 37 | inline void PushEquals() { PushText("="); } 38 | void Print(std::ostream& out) const; 39 | void Clear(); 40 | 41 | std::list terms; 42 | }; 43 | 44 | 45 | } //namespace Math 46 | 47 | #endif 48 | -------------------------------------------------------------------------------- /math/MatrixPrinter.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_MATRIX_PRINTER_H 2 | #define MATH_MATRIX_PRINTER_H 3 | 4 | #include "MatrixTemplate.h" 5 | 6 | namespace Math { 7 | 8 | struct MatrixPrinter 9 | { 10 | enum Mode { Normal, AsciiShade, PlusMinus }; 11 | 12 | MatrixPrinter(const fMatrix& m,Mode mode=Normal); 13 | MatrixPrinter(const dMatrix& m,Mode mode=Normal); 14 | MatrixPrinter(const cMatrix& m,Mode mode=Normal); 15 | void Print(std::ostream& out,int indent=0) const; 16 | 17 | const fMatrix* fm; 18 | const dMatrix* dm; 19 | const cMatrix* cm; 20 | char delim,bracket; 21 | Mode mode; 22 | }; 23 | 24 | std::ostream& operator <<(std::ostream& out,const MatrixPrinter& mp); 25 | 26 | } //namespace Math 27 | 28 | #endif 29 | -------------------------------------------------------------------------------- /math/QuasiNewton.h: -------------------------------------------------------------------------------- 1 | #ifndef QUASI_NEWTON_H 2 | #define QUASI_NEWTON_H 3 | 4 | #include "LDL.h" 5 | 6 | namespace Math { 7 | 8 | /** @ingroup Math 9 | * @brief Maintains the Cholesky decomposition of the hessian H over 10 | * Quasi-Newton steps. 11 | * 12 | * BFGS sets H' = H + q*qt / qt*s - Ht*s*st*H/st*H*s 13 | * DFS sets H' = H + s*st / st*q - Ht*q*qt*H/qt*H*q 14 | * where s = x - x0 15 | * q = grad - grad0 16 | * 17 | * BFGS is usually considered more stable than the latter. 18 | */ 19 | struct QNHessianUpdater 20 | { 21 | QNHessianUpdater(); 22 | ///set the initial hessian matrix 23 | void SetHessian(const Matrix& H) { ldl.set(H); } 24 | ///form the hessian matrix 25 | void GetHessian(Matrix& H) const { ldl.getA(H); } 26 | ///solve x=H^-1*b 27 | void BackSub(const Vector& b,Vector& x) const { ldl.backSub(b,x); } 28 | bool IsValidUpdate(const Vector& s,const Vector& q) { return (s.dot(q)>0); } 29 | bool UpdateBFGS(const Vector& s,const Vector& q); 30 | bool UpdateDFS(const Vector& s,const Vector& q); 31 | bool IsPositiveDefinite(Real tol=0) const; 32 | void MakePositiveDefinite(Real resetValue=1); 33 | 34 | LDLDecomposition ldl; 35 | int verbose; 36 | Real tolerance; 37 | 38 | //temporary 39 | Vector temp,Hs,upd; 40 | Matrix tempLDL; 41 | }; 42 | 43 | 44 | } //namespace Math 45 | 46 | #endif 47 | -------------------------------------------------------------------------------- /math/RowEchelon.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_ROW_ECHELON_H 2 | #define MATH_ROW_ECHELON_H 3 | 4 | #include "MatrixTemplate.h" 5 | #include 6 | 7 | namespace Math { 8 | 9 | /** @ingroup Math 10 | * @brief Compute reduced row-eschelon form for a matrix A. 11 | * 12 | * Back-substitution of Ax=b is done by providing b at initialization. 13 | */ 14 | template 15 | class RowEchelon 16 | { 17 | public: 18 | typedef MatrixTemplate MatrixT; 19 | typedef VectorTemplate VectorT; 20 | 21 | RowEchelon(); 22 | RowEchelon(const MatrixT& A); 23 | RowEchelon(const MatrixT& A,const VectorT& b); 24 | RowEchelon(const MatrixT& A,const MatrixT& B); 25 | 26 | void set(const MatrixT& A); 27 | void set(const MatrixT& A,const VectorT& b); 28 | void set(const MatrixT& A,const MatrixT& B); 29 | void backSub(VectorT& x) const; 30 | int getRank() const; 31 | int getNull() const; 32 | /// Returns a orthonormal basis for the nullspace in the columns of N 33 | void getNullspace(MatrixT& N) const; 34 | /// Calculates a pseudoinverse x0 as well as a nullspace matrix N 35 | void getAllSolutions(VectorT& x0,MatrixT& N) const; 36 | 37 | //helpers 38 | void calcFirstEntries(); 39 | 40 | MatrixT R; 41 | MatrixT EB; 42 | std::vector firstEntry; /// 46 | bool IsRowEchelon(const MatrixTemplate& A); 47 | template 48 | bool IsReducedRowEchelon(const MatrixTemplate& A); 49 | 50 | } //namespace Math 51 | 52 | 53 | #endif 54 | -------------------------------------------------------------------------------- /math/VectorPrinter.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_VECTOR_PRINTER_H 2 | #define MATH_VECTOR_PRINTER_H 3 | 4 | #include "VectorTemplate.h" 5 | 6 | namespace Math { 7 | 8 | struct VectorPrinter 9 | { 10 | enum Mode { Normal, AsciiShade, PlusMinus }; 11 | 12 | VectorPrinter(const fVector& v,Mode mode=Normal); 13 | VectorPrinter(const dVector& v,Mode mode=Normal); 14 | VectorPrinter(const cVector& v,Mode mode=Normal); 15 | void Print(std::ostream& out) const; 16 | 17 | const fVector* fv; 18 | const dVector* dv; 19 | const cVector* cv; 20 | char delim,bracket; 21 | Mode mode; 22 | }; 23 | 24 | std::ostream& operator <<(std::ostream& out,const VectorPrinter& vp); 25 | 26 | } //namespace Math 27 | 28 | #endif 29 | 30 | -------------------------------------------------------------------------------- /math/fastmath.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_FASTMATH_H 2 | #define MATH_FASTMATH_H 3 | 4 | /** @file fastmath.h 5 | * @ingroup Math 6 | * @brief Miscellaneous lightweight math routines. 7 | */ 8 | 9 | unsigned int fastlog2(unsigned int v) 10 | { 11 | const unsigned int b[] = {0x2, 0xC, 0xF0, 0xFF00, 0xFFFF0000}; 12 | const unsigned int S[] = {1, 2, 4, 8, 16}; 13 | int i; 14 | 15 | //register unsigned int r = 0; // result of log2(v) will go here 16 | unsigned int r = 0; // result of log2(v) will go here 17 | for (i = 4; i >= 0; i--) { // unroll for speed... 18 | if (v & b[i]) { 19 | v >>= S[i]; 20 | r |= S[i]; 21 | } 22 | } 23 | return r; 24 | } 25 | 26 | #endif 27 | -------------------------------------------------------------------------------- /math/format.h: -------------------------------------------------------------------------------- 1 | /********************************************************************** 2 | * Primitive Format: 3 | * class ClassName 4 | * { 5 | * ClassName() constructors (WARNING default should not initialize anything -- not zero!) 6 | * operator*=() inplace operators 7 | * operator Other() cast operators 8 | * op() efficient operator methods in the form this=arg1 op arg2 ... 9 | * setX() initializers 10 | * getX() extractors 11 | * inplaceX() inplace modifiers 12 | * load/save() binary file io 13 | * otherMethods() other methods 14 | * 15 | * attributes 16 | * } 17 | * external functions 18 | **********************************************************************/ 19 | -------------------------------------------------------------------------------- /math/infnan.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_INFNAN_H 2 | #define MATH_INFNAN_H 3 | 4 | #include 5 | 6 | #ifndef INFINITY 7 | #include 8 | #endif //INFINITY 9 | 10 | /** @file math/infnan.h 11 | * @ingroup Math 12 | * @brief Cross-platform infinity and not-a-number routines. 13 | * 14 | * Warning: if INFINITY is not defined as a constant, this uses 15 | * the STL numeric_limits::infinity() call. Global static members 16 | * set to Inf will NOT necessarily be initialized properly on certain 17 | * platforms, e.g., Windows. The solution is to avoid declaring static 18 | * variables equal to infinity. 19 | */ 20 | 21 | namespace Math { 22 | 23 | /** @addtogroup Math */ 24 | /*@{*/ 25 | 26 | 27 | #ifdef INFINITY 28 | const static double dInf = INFINITY; 29 | const static float fInf = INFINITY; 30 | #else 31 | const static double dInf = std::numeric_limits::infinity(); 32 | const static float fInf = std::numeric_limits::infinity(); 33 | #endif // INFINITY 34 | 35 | 36 | ///Returns nonzero if x is not-a-number (NaN) 37 | int IsNaN(double x); 38 | int IsNaN(float x); 39 | ///Returns nonzero unless x is infinite or a NaN 40 | int IsFinite(double x); 41 | int IsFinite(float x); 42 | ///Returns +1 if x is +inf, -1 if x is -inf, and 0 otherwise 43 | int IsInf(double x); 44 | int IsInf(float x); 45 | 46 | /*@}*/ 47 | } //namespace Math 48 | 49 | #endif 50 | -------------------------------------------------------------------------------- /math/interpolate.h: -------------------------------------------------------------------------------- 1 | #ifndef INTERPOLATE_H 2 | #define INTERPOLATE_H 3 | 4 | #include "VectorTemplate.h" 5 | #include "MatrixTemplate.h" 6 | 7 | /** @file math/interpolate.h 8 | * @ingroup Math 9 | * @brief Convenience functions for linear interpolation of vectors and 10 | * matrices 11 | */ 12 | 13 | /** @addtogroup Math */ 14 | /*@{*/ 15 | 16 | namespace Math { 17 | 18 | template 19 | void interpolate(const type& a, const type& b, Real u, type& x) 20 | { 21 | x=(One-u)*a + u*b; 22 | } 23 | 24 | 25 | template 26 | void interpolate(const VectorTemplate& a, const VectorTemplate& b, Real u, VectorTemplate& x) 27 | { 28 | x.resize(a.n); 29 | x.mul(a,(One-u)); 30 | x.madd(b,u); 31 | } 32 | 33 | template 34 | void interpolate(const MatrixTemplate& a, const MatrixTemplate& b, Real u, MatrixTemplate& x) 35 | { 36 | x.resize(a.m,a.n); 37 | x.mul(a,(One-u)); 38 | x.madd(b,u); 39 | } 40 | 41 | } //namespace Math 42 | 43 | /*@}*/ 44 | 45 | #endif 46 | -------------------------------------------------------------------------------- /math/matrix.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_MATRIX_H 2 | #define MATH_MATRIX_H 3 | 4 | #include "MatrixTemplate.h" 5 | #include "vector.h" 6 | 7 | namespace Math { 8 | typedef MatrixTemplate Matrix; 9 | } 10 | 11 | #endif 12 | -------------------------------------------------------------------------------- /math/polynomial.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_POLYNOMIAL_H 2 | #define MATH_POLYNOMIAL_H 3 | 4 | #include "misc.h" 5 | 6 | namespace Math { 7 | 8 | namespace Polynomial { 9 | 10 | //alias for x^i 11 | template 12 | inline T BasisTerm(const T x, int i) { return IntegerPower(x,i); } 13 | 14 | //kth derivative of x^i 15 | template 16 | T BasisTerm_Dk(const T x, int i,int k) 17 | { 18 | if(k>i) return 0; 19 | return (T)FactorialTruncated(i,k)*BasisTerm(x,i-k); 20 | } 21 | 22 | //fills in p[i] with x^i, p must have size degree+1 23 | template 24 | void Basis(const T x, int degree, T p[]) 25 | { 26 | p[0]=(T)1; 27 | for(int i=1;i<=degree;i++) p[i]=x*p[i-1]; 28 | } 29 | 30 | //fills in p[i] with kth derivative of x^i, p must have size degree+1 31 | template 32 | void Basis_Dx(const T x, int degree, T p[]) 33 | { 34 | Basis(x,degree,p); 35 | for(int i=degree;i>=1;i--) p[i]=Real(i)*x*p[i-1]; 36 | p[0]=0; 37 | } 38 | 39 | template 40 | void Basis_DDx(const T x, int degree, T p[]) 41 | { 42 | Basis(x,degree,p); 43 | for(int i=degree;i>=2;i--) p[i]=Real(i*(i-1))*x*p[i-2]; 44 | p[0]=0; if(degree<1) return; 45 | p[1]=0; 46 | } 47 | 48 | //The kth derivative of the basis 49 | template 50 | void Basis_Dkx(const T x, int degree, T p[], int k) 51 | { 52 | Basis(x,degree,p); 53 | for(int i=degree;i>=k;i--) p[i]=Real(FactorialTruncated(i,k))*x*p[i-k]; 54 | int end=(k SparseMatrix; 10 | 11 | } //namespace Math 12 | 13 | #endif 14 | -------------------------------------------------------------------------------- /math/sparsevector.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_SPARSE_VECTOR_H 2 | #define MATH_SPARSE_VECTOR_H 3 | 4 | #include "SparseVectorTemplate.h" 5 | 6 | namespace Math { 7 | 8 | typedef SparseVectorTemplate SparseVector; 9 | 10 | } //namespace Math 11 | 12 | #endif 13 | -------------------------------------------------------------------------------- /math/specialfunctions.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_SPECIAL_FUNCTIONS_H 2 | #define MATH_SPECIAL_FUNCTIONS_H 3 | 4 | #include "math.h" 5 | 6 | namespace Math { 7 | 8 | double Gamma(double x); 9 | double LogGamma(double x); 10 | double Beta(double x,double y); 11 | double LogBeta(double x,double y); 12 | 13 | } //namespace Math 14 | 15 | #endif 16 | -------------------------------------------------------------------------------- /math/vector.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_VECTOR_H 2 | #define MATH_VECTOR_H 3 | 4 | #include "VectorTemplate.h" 5 | 6 | namespace Math { 7 | typedef VectorTemplate Vector; 8 | } 9 | 10 | #endif 11 | -------------------------------------------------------------------------------- /math3d/AABB2D.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH3D_AABB2D_H 2 | #define MATH3D_AABB2D_H 3 | 4 | #include "Point.h" 5 | #include 6 | class File; 7 | 8 | namespace Math3D { 9 | 10 | /** @ingroup Math3D 11 | * @brief A 2D axis-aligned bounding box 12 | */ 13 | struct AABB2D 14 | { 15 | AABB2D(); 16 | AABB2D(const Vector2& bmin,const Vector2& bmax); 17 | AABB2D(const AABB2D&); 18 | bool Read(File& f); 19 | bool Write(File& f) const; 20 | 21 | void justify(); ///> (std::istream& in, Cylinder3D& b); 41 | 42 | } //namespace Math3D 43 | 44 | #endif 45 | -------------------------------------------------------------------------------- /math3d/Ellipsoid3D.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH3D_ELLIPSOID_H 2 | #define MATH3D_ELLIPSOID_H 3 | 4 | #include "LocalCoordinates3D.h" 5 | #include "Line3D.h" 6 | 7 | namespace Math3D { 8 | 9 | /** @brief A 3D ellipsoid 10 | * @ingroup Math3D 11 | * 12 | * The ellipsoid is the centered unit sphere [-1,1]^3 set in the scaled local 13 | * coordinate system. That is, the center is at the origin, and its 14 | * major axes are {xbasis,ybasis,zbasis} with radii {dims.x,dims.y,dims.z}. 15 | */ 16 | struct Ellipsoid3D : public ScaledLocalCoordinates3D 17 | { 18 | bool contains(const Point3D& pt) const; 19 | bool intersects(const Line3D& l, Real* t1=NULL, Real* t2=NULL) const; 20 | bool intersects(const Segment3D& s, Real* t1=NULL, Real* t2=NULL) const; 21 | void getAABB(AABB3D& bb) const; 22 | }; 23 | 24 | std::ostream& operator << (std::ostream& out,const Ellipsoid3D& b); 25 | std::istream& operator >> (std::istream& in, Ellipsoid3D& b); 26 | 27 | } //namespace Math3D 28 | 29 | #endif 30 | 31 | -------------------------------------------------------------------------------- /math3d/LinearlyDependent.cpp: -------------------------------------------------------------------------------- 1 | #include "LinearlyDependent.h" 2 | 3 | namespace Math3D { 4 | 5 | template 6 | bool LinearlyDependent_Robust_Template(const VT& a, const VT& b, Real& c, bool& cb, Real eps) { 7 | Real aDotB = a.dot(b); 8 | Real aNorm2 = a.normSquared(); 9 | if(aNorm2 > Abs(aDotB)) { 10 | cb = false; 11 | c = aDotB/aNorm2; 12 | Real aNorm = Sqrt(aNorm2); 13 | Real relEps = eps*aNorm; 14 | for(int i=0;i(a,b,c,cb,eps); 38 | } 39 | 40 | bool LinearlyDependent_Robust(const Vector3& a, const Vector3& b, Real& c, bool& cb, Real eps) { 41 | return LinearlyDependent_Robust_Template(a,b,c,cb,eps); 42 | } 43 | 44 | bool LinearlyDependent_Robust(const Vector4& a, const Vector4& b, Real& c, bool& cb, Real eps) { 45 | return LinearlyDependent_Robust_Template(a,b,c,cb,eps); 46 | } 47 | 48 | } //namespace Math 49 | -------------------------------------------------------------------------------- /math3d/LinearlyDependent.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH3D_LINEARLY_DEPENDENT_H 2 | #define MATH3D_LINEARLY_DEPENDENT_H 3 | 4 | #include "primitives.h" 5 | 6 | namespace Math3D { 7 | 8 | //Robust determination of linear dependence. 9 | //Return true if the vectors are dependent. 10 | //Single-vector versions: 11 | // Returns a constant c s.t. they're linearly dependent within rel error eps 12 | // and |c| <= 1. 13 | // 2 cases, (1) a*c = b with maxabs(a*c-b)/|a| <= eps. 14 | // (2) a = c*b with maxabs(a-c*b)/|b| <= eps. 15 | // in case 1, cb = false, in case 2, cb=true. 16 | // c is chosen by pseudoinverse 17 | //Matrix versions: 18 | // Returns a vector c s.t. A*c = 0. All coefficients |ci| <= 1 19 | // At least one ci = 1. 20 | 21 | bool LinearlyDependent_Robust(const Vector2& a, const Vector2& b, Real& c, bool& cb, Real eps = Epsilon); 22 | bool LinearlyDependent_Robust(const Vector3& a, const Vector3& b, Real& c, bool& cb, Real eps = Epsilon); 23 | bool LinearlyDependent_Robust(const Vector4& a, const Vector4& b, Real& c, bool& cb, Real eps = Epsilon); 24 | 25 | } 26 | 27 | #endif 28 | -------------------------------------------------------------------------------- /math3d/Plane2D.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH3D_PLANE2D_H 2 | #define MATH3D_PLANE2D_H 3 | 4 | #include "Point.h" 5 | 6 | namespace Math3D { 7 | 8 | struct Line2D; 9 | struct Plane2D; 10 | struct Segment2D; 11 | typedef Line2D Ray2D; 12 | struct AABB2D; 13 | 14 | /** @brief A 2D plane class 15 | * @ingroup Math3D 16 | * 17 | * Represents plane with a normal and offset such that x on the plane 18 | * satisfy dot(normal,x) = offset. 19 | */ 20 | struct Plane2D 21 | { 22 | void setPointNormal(const Point2D& a, const Vector2& n); 23 | void setLine(const Line2D& l); 24 | void setPoints(const Point2D& a, const Point2D& b); 25 | void setTransformed(const Plane2D& pin, const Matrix3& xform); 26 | 27 | Real distance(const Point2D& v) const; 28 | void project(const Point2D& in, Point2D& out) const; /// 37 | ///if 0, they don't intersect, pt is intersection "point at infinty".
38 | ///1, it's a point returned in pt
39 | ///2, the planes are identical 40 | int allIntersections(const Plane2D& p,Vector2& pt) const; 41 | 42 | bool Read(File& f); 43 | bool Write(File& f) const; 44 | 45 | Vector2 normal; 46 | Real offset; 47 | }; 48 | 49 | } //namespace Math3D 50 | 51 | #endif 52 | -------------------------------------------------------------------------------- /math3d/Point.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH3D_POINT_H 2 | #define MATH3D_POINT_H 3 | 4 | #include "primitives.h" 5 | 6 | namespace Math3D { 7 | 8 | typedef Vector2 Point2D; 9 | typedef Vector3 Point3D; 10 | typedef Vector4 Point4D; 11 | 12 | } //namespace Math3D 13 | 14 | #endif 15 | -------------------------------------------------------------------------------- /math3d/Ray2D.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH3D_RAY2D_H 2 | #define MATH3D_RAY2D_H 3 | 4 | #include "Line2D.h" 5 | 6 | namespace Math3D { 7 | 8 | //TODO: ray-specific routines 9 | typedef Line2D Ray2D; 10 | 11 | } //namespace Math3D 12 | 13 | #endif 14 | -------------------------------------------------------------------------------- /math3d/Ray3D.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH3D_RAY3D_H 2 | #define MATH3D_RAY3D_H 3 | 4 | #include "Line3D.h" 5 | 6 | namespace Math3D { 7 | 8 | struct Ray3D : public Line3D 9 | { 10 | Real closestPoint(const Point3D& in, Point3D& out) const; 11 | Real distance(const Point3D& pt) const; 12 | bool intersects(const Line3D&, Real* t=NULL, Real* u=NULL, Real epsilon=0) const; //t is the parameter of this ray, u is the line 13 | bool intersects(const Ray3D&, Real* t=NULL, Real* u=NULL, Real epsilon=0) const; //t is the parameter of this ray, u is the other ray 14 | bool intersects(const AABB3D&, Real& tmin, Real& tmax) const; 15 | void closestPoint(const Line3D&,Real& t,Real& u) const; //same comment as above 16 | void closestPoint(const Ray3D&,Real& t,Real& u) const; //same comment as above 17 | Real distance(const AABB3D& bb) const; 18 | Real distance(const AABB3D& bb, Real& tclosest, Vector3& bbclosest) const; 19 | }; 20 | 21 | 22 | } //namespace Math3D 23 | 24 | #endif 25 | -------------------------------------------------------------------------------- /math3d/Segment3D.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH3D_SEGMENT3D_H 2 | #define MATH3D_SEGMENT3D_H 3 | 4 | #include "Point.h" 5 | 6 | namespace Math3D { 7 | 8 | struct Line3D; 9 | struct Plane3D; 10 | struct AABB3D; 11 | 12 | struct Segment3D 13 | { 14 | void setTransformed(const Segment3D&, const Matrix4& xform); 15 | void getLine(Line3D& l) const; 16 | void getAABB(AABB3D& bb) const; 17 | Real distance(const Point3D& p) const; 18 | Real closestPointParameter(const Point3D& in) const; 19 | Real closestPoint(const Point3D& in, Point3D& out) const; //returns the parameter value of the point 20 | void closestPoint(const Segment3D&,Real& t,Real& u) const; //same comment as above 21 | Real distance(const Segment3D&) const; 22 | void eval(Real t, Point3D& out) const; 23 | Point3D eval(Real t) const; 24 | bool intersects(const AABB3D&) const; 25 | bool intersects(const AABB3D&, Real& tmin, Real& tmax) const; 26 | Real distance(const AABB3D& bb) const; 27 | Real distance(const AABB3D& bb, Real& tclosest, Point3D& bbclosest) const; 28 | bool Read(File& f); 29 | bool Write(File& f) const; 30 | 31 | Point3D a,b; 32 | }; 33 | 34 | std::ostream& operator << (std::ostream& out,const Segment3D& s); 35 | std::istream& operator >> (std::istream& in,Segment3D& s); 36 | 37 | } //namespace Math3D 38 | 39 | #endif 40 | -------------------------------------------------------------------------------- /math3d/basis.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH3D_BASIS_H 2 | #define MATH3D_BASIS_H 3 | 4 | #include "primitives.h" 5 | 6 | /** @file math3d/basis.h 7 | * @ingroup Math3D 8 | * @brief Utilities to compute special orthogonal bases (that is, rotation 9 | * matrices). 10 | */ 11 | 12 | namespace Math3D { 13 | 14 | /** @addtogroup Math3D */ 15 | /*@{*/ 16 | 17 | /// Computes the perpendicular vector y s.t. x,y is a rotation from the 18 | /// standard basis. 19 | inline void GetCanonicalBasis(const Vector2& x,Vector2&y) { 20 | y.setPerpendicular(x); 21 | } 22 | /// Computes vectors y,z s.t. x,y,z is a (minimal) rotation from the 23 | /// standard basis. 24 | inline void GetCanonicalBasis(const Vector3& x,Vector3&y,Vector3& z) { 25 | Real scale; 26 | if(FuzzyEquals(x.x,-1.0)) { //A complete flip of the basis 27 | y.set(0.0,-1.0,0.0); 28 | z.set(0.0,0.0,1.0); 29 | return; 30 | } 31 | else scale = 1.0/(1.0+x.x); 32 | y.x = -x.y; 33 | y.y = x.x + scale*Sqr(x.z); 34 | y.z = -scale*x.y*x.z; 35 | z.x = -x.z; 36 | z.y = -scale*x.y*x.z; 37 | z.z = x.x + scale*Sqr(x.y); 38 | } 39 | 40 | /*@}*/ 41 | 42 | } //namespace Math3D 43 | 44 | #endif 45 | -------------------------------------------------------------------------------- /math3d/inlinetypes.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH3D_INLINE_TYPES_H 2 | #define MATH3D_INLINE_TYPES_H 3 | 4 | #include 5 | 6 | namespace Math3D { 7 | 8 | using namespace Math; 9 | 10 | typedef Real vec2_t [2]; 11 | typedef Real vec3_t [3]; 12 | typedef Real vec4_t [4]; 13 | typedef Real matrix3_t [3][4]; 14 | typedef Real matrix4_t [4][4]; 15 | 16 | } 17 | 18 | #endif 19 | -------------------------------------------------------------------------------- /math3d/interpolate.cpp: -------------------------------------------------------------------------------- 1 | #include "interpolate.h" 2 | #include "rotation.h" 3 | #include 4 | 5 | namespace Math3D { 6 | 7 | void interpolateRotation(const Matrix2& a, const Matrix2& b, Real u, Matrix2& x ) 8 | { 9 | Real atheta = Atan2(a(1,0),a(0,0)); 10 | Real btheta = Atan2(b(1,0),b(0,0)); 11 | Real xtheta = AngleInterp(atheta,btheta,u); 12 | x.setRotate(xtheta); 13 | } 14 | 15 | void interpolateRotation(const Matrix3& a, const Matrix3& b, Real u, Matrix3& x) 16 | { 17 | QuaternionRotation qa,qb,qx; 18 | qa.setMatrix(a); 19 | qb.setMatrix(b); 20 | qx.slerp(qa,qb,u); 21 | qx.inplaceNormalize(); 22 | qx.getMatrix(x); 23 | } 24 | 25 | } //namespace Math3d 26 | -------------------------------------------------------------------------------- /math3d/quatinline.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "quatinline.h" 3 | #include 4 | #include 5 | 6 | namespace Math3D { 7 | 8 | void quat_slerp(quat_t out, const quat_t a, const quat_t b, Real t) 9 | { 10 | //a + b unit quaternions? 11 | /* angle theta is defined as 12 | cos(theta)*|a||b| = 13 | */ 14 | Real dot = quat_dot(a,b); 15 | if(FuzzyEquals(dot,One)) //axes are the same axis 16 | { 17 | quat_equal(out,b); 18 | return; 19 | } 20 | else if(FuzzyEquals(dot,-One)) //axes are opposing axis 21 | { 22 | LOG4CXX_ERROR(KrisLibrary::logger(), "Quaternions on opposing sides of unit sphere\n"); 23 | return; 24 | } 25 | Real theta = Acos(dot); 26 | Real sininv = Sin(theta); 27 | sininv = Inv(sininv); 28 | 29 | quat_multiply(out, a, Sin((One-t)*theta)*sininv); 30 | quat_t temp; 31 | quat_multiply(temp, b, Sin(t*theta)*sininv); 32 | quat_add(out, out, temp); 33 | } 34 | 35 | } //namespace Math3D 36 | -------------------------------------------------------------------------------- /math3d/quatinline.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH3D_QUATERNION_INLINE_H 2 | #define MATH3D_QUATERNION_INLINE_H 3 | 4 | #include "vecinline.h" 5 | 6 | namespace Math3D { 7 | 8 | typedef vec4_t quat_t; 9 | 10 | #define quat_zero vec4_zero 11 | #define quat_equal vec4_equal 12 | #define quat_multiply vec4_multiply 13 | #define quat_add vec4_add 14 | #define quat_dot vec4_dot 15 | #define quat_normalize vec4_normalize 16 | 17 | void quat_slerp(quat_t x, const quat_t a, const quat_t b, Real t); 18 | 19 | } 20 | 21 | #endif 22 | -------------------------------------------------------------------------------- /math3d/random.cpp: -------------------------------------------------------------------------------- 1 | #include "random.h" 2 | 3 | namespace Math3D { 4 | 5 | /* 6 | void RandRotation(Quaternion& q) 7 | { 8 | const int maxIters = 20; //small chance of not being uniformly distributed 9 | int iters=0; 10 | Real n; 11 | do { 12 | q.w = Rand(-1,1); 13 | q.x = Rand(-1,1); 14 | q.y = Rand(-1,1); 15 | q.z = Rand(-1,1); 16 | n=q.normSquared(); 17 | iters++; if(iters > maxIters) break; 18 | } while(n > One && n < Epsilon); 19 | q /= Sqrt(n); 20 | } 21 | */ 22 | 23 | void RandRotation(Quaternion& q) 24 | { 25 | const int maxIters = 20; //small chance of not being uniformly distributed 26 | int iters=0; 27 | Real x2y2,w2z2; 28 | do { 29 | q.w = Rand(-1,1); 30 | q.x = Rand(-1,1); 31 | q.y = Rand(-1,1); 32 | q.z = Rand(-1,1); 33 | x2y2=Sqr(q.x)+Sqr(q.y); 34 | w2z2=Sqr(q.w)+Sqr(q.z); 35 | iters++; if(iters > maxIters) break; 36 | } while(x2y2 > One || w2z2 > One); 37 | Real u=Sqrt((One-x2y2)/w2z2); 38 | q.z*=u; 39 | q.w*=u; 40 | } 41 | 42 | 43 | } //namespace Math3D 44 | -------------------------------------------------------------------------------- /meshing/ClosestPoint.cpp: -------------------------------------------------------------------------------- 1 | #include "ClosestPoint.h" 2 | #include 3 | #include 4 | #include 5 | #include "structs/FastFindHeap.h" 6 | using namespace std; 7 | 8 | namespace Meshing { 9 | 10 | int ClosestPointDescent(const TriMeshWithTopology& m,const Vector3& p,int tri,Vector3& cp) 11 | { 12 | Assert(m.tris.size() == m.triNeighbors.size()); 13 | Assert(tri >= 0 && tri < (int)m.tris.size()); 14 | Triangle3D t; 15 | Vector3 temp; 16 | Real closestd=Inf; 17 | FastFindHeap q; //sorted from highest to lowest 18 | set visited; 19 | q.push(tri,-Inf); 20 | while(!q.empty()) { 21 | int curtri = q.top(); q.pop(); 22 | visited.insert(curtri); 23 | 24 | m.GetTriangle(curtri,t); 25 | temp = t.closestPoint(p); 26 | Real d=temp.distance(p); 27 | if(d < closestd) { 28 | tri = curtri; 29 | closestd = d; 30 | cp = temp; 31 | //traverse to neighbors 32 | for(int i=0;i<3;i++) { 33 | int neighbor = m.triNeighbors[curtri][i]; 34 | if(neighbor >= 0) { 35 | if(visited.find(neighbor)==visited.end()) 36 | q.adjust(neighbor,-d); 37 | } 38 | } 39 | } 40 | } 41 | return tri; 42 | } 43 | 44 | } //namespace Meshing 45 | -------------------------------------------------------------------------------- /meshing/ClosestPoint.h: -------------------------------------------------------------------------------- 1 | #ifndef MESHING_CLOSEST_POINT_H 2 | #define MESHING_CLOSEST_POINT_H 3 | 4 | #include "TriMeshTopology.h" 5 | 6 | namespace Meshing { 7 | 8 | ///Finds the closest point to p on m by a gradient descent 9 | ///starting from triangle tri 10 | int ClosestPointDescent(const TriMeshWithTopology& m,const Vector3& p,int tri,Vector3& cp); 11 | 12 | } //namespace Meshing 13 | 14 | #endif 15 | -------------------------------------------------------------------------------- /meshing/Expand.h: -------------------------------------------------------------------------------- 1 | #ifndef MESHING_EXPAND_H 2 | #define MESHING_EXPAND_H 3 | 4 | #include "TriMeshTopology.h" 5 | 6 | namespace Meshing { 7 | 8 | void Expand(const TriMeshWithTopology& in,Real distance,int divs,TriMesh& m); 9 | void Expand2Sided(const TriMeshWithTopology& in,Real distance,int divs,TriMesh& m); 10 | 11 | } //namespace Meshing 12 | 13 | #endif 14 | 15 | -------------------------------------------------------------------------------- /meshing/Geodesic.h: -------------------------------------------------------------------------------- 1 | #ifndef MESHING_GEODESIC_H 2 | #define MESHING_GEODESIC_H 3 | 4 | #include "TriMeshTopology.h" 5 | #include 6 | 7 | namespace Meshing { 8 | 9 | /** @ingroup Meshing 10 | * @brief Computes an approximate geodesic distance over a mesh, 11 | * from a single source. 12 | * 13 | * O(n log n) implementation. 14 | */ 15 | class ApproximateGeodesic 16 | { 17 | public: 18 | ApproximateGeodesic(const TriMeshWithTopology& mesh); 19 | void ComputeVirtualEdges(); 20 | void SolveFromVertex(int v); 21 | void SolveFromTri(int tri,const Vector3& pt); 22 | Real Distance(int tri,const Vector3& pt) const; 23 | void ExpandVert(int v); 24 | void UpdateDistance(int v,Real d); 25 | 26 | const TriMeshWithTopology& mesh; 27 | vector triangleWeights; //by default empty means a coefficient of 1 28 | vector vertCosts; 29 | vector vertColor; 30 | FixedSizeHeap h; 31 | //edges to propagate values to from obtuse triangles to support (along with the unfolded virtual point 32 | struct VirtualEdge 33 | { 34 | int vertex1,vertex2; 35 | Vector2 planePos1,planePos2; 36 | }; 37 | vector virtualEdges; 38 | //co-edges from support vertices to obtuse triangles 39 | vector > incomingVirtualEdges; 40 | }; 41 | 42 | } //namespace Meshing 43 | 44 | #endif 45 | -------------------------------------------------------------------------------- /meshing/LSConformalMapping.h: -------------------------------------------------------------------------------- 1 | #ifndef MESHING_LS_CONFORMAL_MAPPING_H 2 | #define MESHING_LS_CONFORMAL_MAPPING_H 3 | 4 | #include "TriMeshAtlas.h" 5 | 6 | namespace Meshing { 7 | 8 | /** @ingroup Meshing 9 | * @brief An approximately-conformal parameterization a genus-0 10 | * mesh, found by a least-squares method. 11 | * 12 | * Implements the method "Least Squares Conformal Maps for Automatic 13 | * Texture Atlas Generation by Levy et.al. in Siggraph 2002. 14 | */ 15 | class LSConformalMapping 16 | { 17 | public: 18 | LSConformalMapping(TriMeshWithTopology& mesh,TriMeshChart& chart); 19 | bool Calculate(); 20 | 21 | TriMeshWithTopology& mesh; 22 | TriMeshChart& chart; 23 | }; 24 | 25 | } //namespace Meshing 26 | 27 | #endif 28 | 29 | -------------------------------------------------------------------------------- /meshing/TriMeshAtlas.h: -------------------------------------------------------------------------------- 1 | #ifndef MESHING_TRIMESH_ATLAS_H 2 | #define MESHING_TRIMESH_ATLAS_H 3 | 4 | #include "TriMeshTopology.h" 5 | #include 6 | 7 | namespace Meshing { 8 | 9 | /** @ingroup Meshing 10 | * @brief A chart maps a genus 0 triangle mesh to a 2d disk 11 | */ 12 | struct TriMeshChart 13 | { 14 | TriMeshChart(TriMeshWithTopology& _mesh) : mesh(_mesh) {} 15 | 16 | TriMeshWithTopology& mesh; 17 | vector coordinates; 18 | }; 19 | 20 | /** @ingroup Meshing 21 | * @brief TODO: a non-genus 0 mesh partitioned into charts */ 22 | struct TriMeshAtlas 23 | { 24 | //vector charts; 25 | }; 26 | 27 | } //namespace Meshing 28 | 29 | #endif 30 | -------------------------------------------------------------------------------- /msvc64/ALL_BUILD.vcxproj.filters: -------------------------------------------------------------------------------- 1 |  2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | -------------------------------------------------------------------------------- /msvc64/INSTALL.vcxproj.filters: -------------------------------------------------------------------------------- 1 |  2 | 3 | 4 | 5 | CMake Rules 6 | 7 | 8 | 9 | 10 | {699748DF-A596-3392-85CB-AE6CDBFCDA00} 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /msvc64/PACKAGE.vcxproj.filters: -------------------------------------------------------------------------------- 1 |  2 | 3 | 4 | 5 | CMake Rules 6 | 7 | 8 | 9 | 10 | {699748DF-A596-3392-85CB-AE6CDBFCDA00} 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /msvc64/ZERO_CHECK.vcxproj.filters: -------------------------------------------------------------------------------- 1 |  2 | 3 | 4 | 5 | CMake Rules 6 | 7 | 8 | 9 | 10 | {699748DF-A596-3392-85CB-AE6CDBFCDA00} 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /msvc64/uninstall.vcxproj.filters: -------------------------------------------------------------------------------- 1 |  2 | 3 | 4 | 5 | 6 | CMake Rules 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | {699748DF-A596-3392-85CB-AE6CDBFCDA00} 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /optimization/BoundedLSQRSolver.h: -------------------------------------------------------------------------------- 1 | #ifndef BOUNDED_LSQR_SOLVER_H 2 | #define BOUNDED_LSQR_SOLVER_H 3 | 4 | #include "LinearProgram.h" 5 | 6 | namespace Optimization { 7 | 8 | /**@brief Solve the bounded least-squares problem 9 | * min||Ax-b||^2 s.t. l <= x <= b 10 | * accepts infinite constraints too. 11 | */ 12 | class BoundedLSQRSolver 13 | { 14 | public: 15 | BoundedLSQRSolver(const Matrix& A,const Vector& b,const Vector& l,const Vector& u); 16 | LinearProgram::Result Solve(Vector& x); 17 | 18 | Matrix A; 19 | Vector b; 20 | Vector l,u; 21 | 22 | int verbose; 23 | Real fTol,gradTol,xTol; 24 | int maxIters; 25 | }; 26 | 27 | } //namespace Optimization 28 | 29 | #endif 30 | -------------------------------------------------------------------------------- /optimization/GLPKInterface.h: -------------------------------------------------------------------------------- 1 | #ifndef OPTIMIZATION_GLPK_INTERFACE_H 2 | #define OPTIMIZATION_GLPK_INTERFACE_H 3 | 4 | #include "LinearProgram.h" 5 | #if HAVE_GLPK 6 | 7 | #include 8 | 9 | #else 10 | #define glp_prob void 11 | #endif 12 | 13 | namespace Optimization { 14 | 15 | /** @ingroup Optimization 16 | * @brief An interface to the GLPK linear program solver. Activated with the 17 | * HAVE_GLPK preprocessor define. 18 | */ 19 | struct GLPKInterface 20 | { 21 | GLPKInterface(); 22 | ~GLPKInterface(); 23 | //easiest interface 24 | void Set(const LinearProgram& LP); 25 | void Set(const LinearProgram_Sparse& LP); 26 | LinearProgram::Result Solve(Vector& xopt); 27 | //low level commands 28 | void Create(int m,int n); 29 | void Clear(); 30 | void SetObjective(const Vector& c,bool minimize=true); 31 | void SetRow(int i,const Vector& Ai); 32 | void SetRowBounds(int i,Real low,Real high); 33 | void SetVariableBounds(int j,Real low,Real high); 34 | 35 | //warm starting the solver 36 | void SetRowBasic(int i); //inactive 37 | void SetRowNonBasic(int i,bool upper=false); //active 38 | void SetVariableBasic(int i); //inactive 39 | void SetVariableNonBasic(int i,bool upper=false); //active 40 | bool GetRowBasic(int i); //inactive 41 | bool GetVariableBasic(int i); //inactive 42 | double GetRowDual(int i); 43 | double GetVariableDual(int j); 44 | 45 | static bool Enabled(); 46 | static void SelfTest(); 47 | 48 | glp_prob* lp; 49 | }; 50 | 51 | } //namespace Optimization 52 | 53 | #endif 54 | -------------------------------------------------------------------------------- /optimization/LPRobust.cpp: -------------------------------------------------------------------------------- 1 | #include "LPRobust.h" 2 | #include 3 | #include 4 | using namespace std; 5 | using namespace Optimization; 6 | 7 | 8 | RobustLPSolver::RobustLPSolver() 9 | :verbose(0) 10 | { 11 | Clear(); 12 | } 13 | 14 | void RobustLPSolver::Clear() 15 | { 16 | initialized=false; 17 | } 18 | 19 | LinearProgram::Result RobustLPSolver::Solve(const LinearProgram& lp) 20 | { 21 | UpdateGLPK(lp); 22 | LinearProgram::Result res=SolveGLPK(); 23 | return res; 24 | } 25 | 26 | LinearProgram::Result RobustLPSolver::Solve(const LinearProgram_Sparse& lp) 27 | { 28 | glpk.Set(lp); 29 | initialized=true; 30 | return SolveGLPK(); 31 | } 32 | 33 | LinearProgram::Result RobustLPSolver::Solve_NewObjective(const LinearProgram& lp) 34 | { 35 | if(!initialized) UpdateGLPK(lp); 36 | else glpk.SetObjective(lp.c,lp.minimize); 37 | LinearProgram::Result res=SolveGLPK(); 38 | return res; 39 | } 40 | 41 | LinearProgram::Result RobustLPSolver::Solve_NewObjective(const LinearProgram_Sparse& lp) 42 | { 43 | if(!initialized) { 44 | glpk.Set(lp); 45 | initialized = true; 46 | } 47 | else glpk.SetObjective(lp.c,lp.minimize); 48 | return SolveGLPK(); 49 | } 50 | 51 | 52 | void RobustLPSolver::UpdateGLPK(const LinearProgram& lp) 53 | { 54 | glpk.Set(lp); 55 | initialized=true; 56 | } 57 | 58 | LinearProgram::Result RobustLPSolver::SolveGLPK() 59 | { 60 | assert(GLPKInterface::Enabled()); 61 | return glpk.Solve(xopt); 62 | } 63 | -------------------------------------------------------------------------------- /optimization/LPRobust.h: -------------------------------------------------------------------------------- 1 | #ifndef OPTIMIZATION_LP_ROBUST_H 2 | #define OPTIMIZATION_LP_ROBUST_H 3 | 4 | #include "GLPKInterface.h" 5 | 6 | namespace Optimization { 7 | 8 | /** @ingroup Optimization 9 | * @brief A class that tries out as many available routines as possible 10 | * to solve an LP. 11 | */ 12 | struct RobustLPSolver 13 | { 14 | RobustLPSolver(); 15 | void Clear(); 16 | 17 | LinearProgram::Result Solve(const LinearProgram& lp); 18 | LinearProgram::Result Solve(const LinearProgram_Sparse& lp); 19 | LinearProgram::Result Solve_NewObjective(const LinearProgram& lp); 20 | LinearProgram::Result Solve_NewObjective(const LinearProgram_Sparse& lp); 21 | void UpdateGLPK(const LinearProgram& lp); 22 | LinearProgram::Result SolveGLPK(); 23 | 24 | GLPKInterface glpk; 25 | bool initialized; 26 | int verbose; 27 | 28 | ///temporary variable, stores the output of the solver 29 | Vector xopt; 30 | }; 31 | 32 | } //namespace Optimization 33 | 34 | #endif 35 | -------------------------------------------------------------------------------- /optimization/LSQRInterface.h: -------------------------------------------------------------------------------- 1 | #ifndef OPTIMIZATION_LSQR_INTERFACE_H 2 | #define OPTIMIZATION_LSQR_INTERFACE_H 3 | 4 | #include 5 | #include 6 | 7 | namespace Optimization 8 | { 9 | using namespace Math; 10 | 11 | /** @ingroup Optimization 12 | * @brief An interface to a sparse least-squares solver (lsqr). 13 | */ 14 | struct LSQRInterface 15 | { 16 | LSQRInterface(); 17 | bool Solve(const SparseMatrix& A,const Vector& b); 18 | 19 | //input quantities 20 | Vector x0; /// 5 | 6 | namespace Optimization 7 | { 8 | using namespace Math; 9 | 10 | /** @ingroup Optimization 11 | * @brief A least-squares problem definition. 12 | * 13 | * Defines the least-squares problem 14 | * min |A*x-b|^2 subject to
15 | * C*x = d (equality constraints)
16 | * E*x <= f (inequality constrants) 17 | */ 18 | struct LeastSquares 19 | { 20 | LeastSquares(); 21 | bool Solve(Vector& x) const; 22 | bool SatisfiesInequalities(const Vector& x) const; 23 | bool SatisfiesEqualities(const Vector& x,Real tol=Epsilon) const; 24 | Real Objective(const Vector& x) const; 25 | void Print(std::ostream& out) const; 26 | void PrintStats(const Vector& x,std::ostream& out) const; 27 | 28 | Matrix A; Vector b; 29 | Matrix Aeq; Vector beq; 30 | Matrix Aineq; Vector bineq; 31 | const Vector* initialPoint; //optional initial feasible point 32 | int verbose; 33 | }; 34 | 35 | } //namespace Optimization 36 | 37 | #endif 38 | -------------------------------------------------------------------------------- /optimization/NewtonSolver.h: -------------------------------------------------------------------------------- 1 | #ifndef OPTIMIZATION_NEWTON_SOLVER_H 2 | #define OPTIMIZATION_NEWTON_SOLVER_H 3 | 4 | #include "NonlinearProgram.h" 5 | #include 6 | 7 | namespace Optimization { 8 | 9 | struct InequalityBarrierNLP; 10 | 11 | /** @ingroup Optimization 12 | * @brief A newton's-method style solver for a NLP. 13 | * 14 | * NOTE: Not tested very thoroughly. 15 | * 16 | * TODO: bound constraints bmin,bmax 17 | * TODO: make this work for inequality constraints d(x) <= 0 18 | */ 19 | struct NewtonSolver 20 | { 21 | NewtonSolver(NonlinearProgram& nlp); 22 | ~NewtonSolver(); 23 | ///Call to initialize the solver after setting the initial point x 24 | void Init(); 25 | ///Use newton's method to solve the NLP using the given number of iters 26 | ConvergenceResult Solve(int& maxIters); 27 | ///Performs a line search in direction (dx,da). 28 | ///returns MaxItersReached on normal exit 29 | ConvergenceResult LineSearch(Real& alpha); 30 | Real Merit(const Vector& x,const Vector& a) const; 31 | 32 | ///state - x is the variable, a is the lagrange multipliers 33 | NonlinearProgram& origProblem; 34 | InequalityBarrierNLP* barrierProblem; 35 | NonlinearProgram* problem; 36 | Vector x,a; 37 | Vector dx,da; 38 | 39 | ///user settings 40 | Vector bmin,bmax; 41 | Real tolf,tolx; 42 | int verbose; 43 | std::vector* S; 44 | 45 | ///temp 46 | Matrix H,Hinv; 47 | Matrix A,AHA,mtemp; 48 | Vector res1,res2,vtemp; 49 | }; 50 | 51 | } //namespace Optimization 52 | 53 | #endif 54 | -------------------------------------------------------------------------------- /optimization/QuadProgPPInterface.h: -------------------------------------------------------------------------------- 1 | #ifndef QUADPROGPP_INTERFACE_H 2 | #define QUADPROGPP_INTERFACE_H 3 | 4 | #include "QuadraticProgram.h" 5 | 6 | namespace Optimization { 7 | 8 | /** @ingroup Optimization 9 | * @brief An interface to the QuadProg++ quadratic programming solver. 10 | * Enable with the HAVE_QUADPROGPP=1 preprocessor define. 11 | * 12 | * Note: I tested this, and it seems to be pretty unreliable. 13 | */ 14 | struct QuadProgPPInterface 15 | { 16 | LinearProgram::Result Solve(const QuadraticProgram& qp,Vector& xopt); 17 | }; 18 | 19 | } //namespace Optimization 20 | 21 | #endif 22 | -------------------------------------------------------------------------------- /optimization/QuadraticProgram.h: -------------------------------------------------------------------------------- 1 | #ifndef OPTIMIZATION_QUADRATIC_PROGRAM_H 2 | #define OPTIMIZATION_QUADRATIC_PROGRAM_H 3 | 4 | #include 5 | #include "LinearProgram.h" 6 | 7 | namespace Optimization { 8 | using namespace Math; 9 | 10 | /** @ingroup Optimization 11 | * @brief Quadratic program definition 12 | * 13 | * Defines the QP 14 | * min 0.5*x'*Pobj*x +qobj'*x
15 | * s.t. q <= Ax <= p 16 | * l <= x <= u 17 | */ 18 | struct QuadraticProgram : public LinearConstraints 19 | { 20 | void Print(std::ostream& out) const; 21 | void Resize(int m,int n); 22 | bool IsValid() const; 23 | Real Objective(const Vector& x) const; 24 | 25 | Matrix Pobj; 26 | Vector qobj; 27 | }; 28 | 29 | } //namespace Optimization 30 | 31 | #endif 32 | 33 | -------------------------------------------------------------------------------- /optimization/RegularizedLinearProgram.h: -------------------------------------------------------------------------------- 1 | #ifndef OPTIMIZATION_MIN_NORM_PROBLEM_H 2 | #define OPTIMIZATION_MIN_NORM_PROBLEM_H 3 | 4 | #include "LinearProgram.h" 5 | #include "QuadraticProgram.h" 6 | 7 | namespace Optimization { 8 | 9 | /** @ingroup Optimization 10 | * @brief Solves a linear program with regularization 11 | * 12 | * Problem is of the form 13 | * min c^t x + ||C x - d|| 14 | * s.t. q <= A x <= p 15 | * l <= x <= u 16 | * where ||.|| is either a 1 or infinity norm 17 | */ 18 | struct RegularizedLinearProgram : public LinearConstraints 19 | { 20 | RegularizedLinearProgram(); 21 | void ResizeObjective(int m,int n) { C.resize(m,n); d.resize(n); } 22 | void ResizeConstraints(int m,int n) { LinearConstraints::Resize(m,n); } 23 | bool IsValid() const; 24 | void Print(std::ostream& out) const; 25 | void Assemble(); /// 6 | 7 | class CSpaceAnalysis 8 | { 9 | public: 10 | void AnalyzeNeighborhood(CSpace* cspace,const Config& x,Real radius,int numSamples); 11 | 12 | struct SetCharacteristics 13 | { 14 | //source data 15 | Config center; 16 | Real sampleRadius; 17 | std::vector points; 18 | 19 | //model of space: vol(Ball(r)) = c*r^d 20 | //where c is an arbitrary constant, d is intrinsicDims 21 | Real intrinsicDims; 22 | 23 | //local models of space (localIntrinsicDims[i] is intrinsic dimension 24 | //at ball of radius localScales[i] 25 | std::vector localIntrinsicDims; 26 | std::vector localScales; 27 | }; 28 | 29 | SetCharacteristics space,feasible,infeasible; 30 | Real feasibleVolume; 31 | std::vector feasibleEigenvector; 32 | }; 33 | 34 | #endif 35 | -------------------------------------------------------------------------------- /planning/FMMMotionPlanner.h: -------------------------------------------------------------------------------- 1 | #ifndef PLANNING_FMM_MOTION_PLANNER_H 2 | #define PLANNING_FMM_MOTION_PLANNER_H 3 | 4 | #include "CSpace.h" 5 | #include "Path.h" 6 | #include "FMM.h" 7 | 8 | class FMMMotionPlanner 9 | { 10 | public: 11 | ///Initialize planner. Use a dynamic domain, dynamic resolution. 12 | FMMMotionPlanner(CSpace* space); 13 | ///Initialize planner. Use a fixed domain with given resolution divs. 14 | FMMMotionPlanner(CSpace* space,const Vector& bmin,const Vector& bmax,int divs = 10); 15 | void Init(const Config& a,const Config& b); 16 | ///Runs a single instance of the FMM at the current resolution, 17 | ///returns true if successful. (Be sure the set the resolution! 18 | ///The default is very coarse.) 19 | bool SolveFMM(); 20 | ///Runs instances of the FMM at increasingly fine resolutions. 21 | ///Returns true if a new feasible path was successfully found within 22 | ///the given time cutoff. Safe to call this multiple times. 23 | bool SolveAnytime(Real time); 24 | 25 | Vector ToGrid(const Vector& q) const; 26 | Vector FromGrid(const Vector& q) const; 27 | Vector FromGrid(const std::vector& pt) const; 28 | 29 | CSpace* space; 30 | Vector bmin,bmax; 31 | bool dynamicDomain; 32 | Vector resolution; 33 | Config start,goal; 34 | ArrayND distances; 35 | MilestonePath solution; 36 | //debug: a path that failed the secondary feasibility check 37 | MilestonePath failedCheck; 38 | }; 39 | 40 | #endif 41 | -------------------------------------------------------------------------------- /planning/Grid2DCSpace.h: -------------------------------------------------------------------------------- 1 | #ifndef GRID_2D_CSPACE_H 2 | #define GRID_2D_CSPACE_H 3 | 4 | #include "CSpaceHelpers.h" 5 | #include 6 | #include 7 | #include 8 | #include "Tabular.h" 9 | using namespace Math3D; 10 | 11 | /** @brief A simple CSpace that lets you add geometric obstacles as 12 | * blocked off grid cells. 13 | * 14 | * Can use euclidean or Linf metric, configured by euclideanSpace. 15 | */ 16 | class Grid2DCSpace : public BoxCSpace 17 | { 18 | public: 19 | Grid2DCSpace(int m,int n,const AABB2D& domain); 20 | void WorldToGrid(const Vector2& world,Vector2& grid); 21 | void GridToWorld(const Vector2& grid,Vector2& world); 22 | void Add(const Triangle2D& tri,bool obstacle=true); 23 | void Add(const AABB2D& bbox,bool obstacle=true); 24 | //void Add(const Polygon2D& poly,bool obstacle=true); 25 | void Add(const Circle2D& sphere,bool obstacle=true); 26 | void Rasterize(CSpace* space); 27 | void DrawGL(); 28 | 29 | virtual void SampleNeighborhood(const Config& c,Real r,Config& x) override; 30 | virtual EdgePlannerPtr PathChecker(const Config& a,const Config& b) override; 31 | EdgePlannerPtr PathChecker(const std::shared_ptr& path); 32 | virtual Real Distance(const Config& x, const Config& y) override; 33 | 34 | bool euclideanSpace; 35 | std::shared_ptr occupied; 36 | }; 37 | 38 | #endif 39 | -------------------------------------------------------------------------------- /planning/Interpolator.h: -------------------------------------------------------------------------------- 1 | #ifndef PLANNING_INTERPOLATOR_H 2 | #define PLANNING_INTERPOLATOR_H 3 | 4 | #include 5 | #include 6 | 7 | /** @ingroup MotionPlanning 8 | * @brief A base class for all 1D interpolators. 9 | */ 10 | class Interpolator 11 | { 12 | public: 13 | virtual ~Interpolator() {} 14 | virtual void Eval(Real u,Config& x) const=0; 15 | virtual Real Length() const=0; 16 | virtual const Config& Start() const=0; 17 | virtual const Config& End() const=0; 18 | virtual Real ParamStart() const { return 0; } 19 | virtual Real ParamEnd() const { return 1; } 20 | }; 21 | 22 | /** @ingroup MotionPlanning 23 | * @brief An interpolator that reverses another one. 24 | */ 25 | class ReverseInterpolator : public Interpolator 26 | { 27 | public: 28 | ReverseInterpolator(const std::shared_ptr& base); 29 | virtual ~ReverseInterpolator() {} 30 | virtual void Eval(Real u,Config& x) const override { base->Eval(1.0-u,x); } 31 | virtual Real Length() const override { return base->Length(); } 32 | virtual const Config& Start() const override { return base->End(); } 33 | virtual const Config& End() const override { return base->Start(); } 34 | 35 | std::shared_ptr base; 36 | }; 37 | 38 | typedef std::shared_ptr InterpolatorPtr; 39 | 40 | #endif -------------------------------------------------------------------------------- /planning/KinodynamicOptimizer.h: -------------------------------------------------------------------------------- 1 | #ifndef PLANNING_KINODYNAMIC_OPTIMIZER_H 2 | #define PLANNING_KINODYNAMIC_OPTIMIZER_H 3 | 4 | #include "KinodynamicMotionPlanner.h" 5 | 6 | class KinodynamicLocalOptimizer : public KinodynamicPlannerBase 7 | { 8 | public: 9 | KinodynamicLocalOptimizer(KinodynamicSpace* s,std::shared_ptr objective); 10 | virtual ~KinodynamicLocalOptimizer(); 11 | void Init(const KinodynamicMilestonePath& path,CSet* goalSet); 12 | virtual void Init(const State& xinit,CSet* goalSet); 13 | virtual bool Plan(int maxIters); 14 | virtual bool Done() const; 15 | virtual bool GetPath(KinodynamicMilestonePath& path); 16 | void ComputeCosts(); 17 | bool DoShortcut(); 18 | bool DoRandomDescent(Real perturbationSize); 19 | bool DoGradientDescent(); 20 | bool DoDDP(); 21 | 22 | enum { Shortcut, RandomDescent, GradientDescent, DDP }; 23 | 24 | std::shared_ptr objective; 25 | KinodynamicMilestonePath bestPath; 26 | Real bestPathCost; 27 | std::vector cumulativeCosts; 28 | 29 | //stats for adaptive method 30 | std::vector methodAvailable; 31 | std::vector methodCounts; 32 | std::vector methodRewards; 33 | std::vector methodCosts; 34 | //temporary 35 | KinodynamicMilestonePath tempPath; 36 | }; 37 | 38 | #endif -------------------------------------------------------------------------------- /planning/PRT.h: -------------------------------------------------------------------------------- 1 | #ifndef ROBOTICS_PRT_H 2 | #define ROBOTICS_PRT_H 3 | 4 | #include "CSpace.h" 5 | 6 | /** @ingroup MotionPlanning 7 | * @brief The PRT (Probabilistic Roadmap of Trees) planner. 8 | * 9 | * Sometimes called SRT (Sampling-Based Roadmap of Trees). 10 | */ 11 | class PRTPlanner 12 | { 13 | public: 14 | typedef Graph::Tree Node; 15 | struct Tree 16 | { 17 | Node* root; 18 | Config centroid; 19 | }; 20 | struct TreeEdge 21 | { 22 | Node* start, *end; 23 | MilestonePath path; 24 | }; 25 | 26 | PRTPlanner(); 27 | virtual ~PRTPlanner(); 28 | virtual void Cleanup(); 29 | virtual void Seed(); 30 | virtual void AddAndGrowTree(const Config& x); 31 | virtual void Expand(); 32 | virtual bool ConnectTrees(int i,int j); 33 | 34 | Graph::Graph treeGraph; 35 | 36 | ///these flags govern the number of seeded trees and their size 37 | int numSeedTrees,seedTreeSize; 38 | ///these flags govern the choice of trees to connect per expansion operation 39 | int numClosestTreesToConnect,numRandomTreesToConnect; 40 | int numStraightLineAttempts,numSingleQueryIterations; 41 | }; 42 | 43 | #endif 44 | -------------------------------------------------------------------------------- /planning/PerturbationCSpace.h: -------------------------------------------------------------------------------- 1 | #ifndef ROBOTICS_PERTURBATION_CSPACE_H 2 | #define ROBOTICS_PERTURBATION_CSPACE_H 3 | 4 | #include "CSpace.h" 5 | #include 6 | 7 | /** @brief A C-space that ensures that a configuration + perturbation[i] 8 | * is feasible, for all i=1,...,N. 9 | */ 10 | class PerturbationCSpace : public CSpace 11 | { 12 | public: 13 | PerturbationCSpace(CSpace* baseSpace,const std::vector& perturbations); 14 | virtual ~PerturbationCSpace(); 15 | virtual void Sample(Config& q) override; 16 | virtual Config Perturb(const Config& q,const Vector& perturbation); 17 | virtual bool IsFeasible(const Config& q,int obstacle) override; 18 | virtual EdgePlannerPtr PathChecker(const Config& a,const Config& b,int obstacle) override; 19 | virtual int NumConstraints() override; 20 | virtual std::string ConstraintName(int obstacle) override; 21 | virtual Real ObstacleDistance(const Config& a) override; 22 | virtual void Properties(PropertyMap& map) override; 23 | 24 | virtual EdgePlannerPtr LocalPlanner(const Config& a,const Config& b,int obstacle); 25 | virtual Real ObstacleDistance(const Config& a,int obstacle); 26 | 27 | CSpace* baseSpace; 28 | std::vector perturbations; 29 | }; 30 | 31 | #endif 32 | -------------------------------------------------------------------------------- /planning/RigidRobot2DCSpace.h: -------------------------------------------------------------------------------- 1 | #ifndef RIGID_ROBOT_2D_CSPACE_H 2 | #define RIGID_ROBOT_2D_CSPACE_H 3 | 4 | #include "Geometric2DCSpace.h" 5 | #include "RigidBodyCSpace.h" 6 | 7 | /** @brief a translating and rotating 2D robot in a 2D workspace. 8 | */ 9 | class RigidRobot2DCSpace : public SE2CSpace 10 | { 11 | public: 12 | RigidRobot2DCSpace(); 13 | RigidRobot2DCSpace(const AABB2D& domain); 14 | void InitConstraints(); 15 | void DrawWorkspaceGL() const; 16 | void DrawRobotGL(const Config& q) const; 17 | void DrawGL(const Config& q) const; 18 | 19 | virtual EdgePlannerPtr PathChecker(const Config& a,const Config& b) override; 20 | virtual EdgePlannerPtr PathChecker(const Config& a,const Config& b,int obstacle) override; 21 | virtual void Properties(PropertyMap&) override; 22 | 23 | Real visibilityEpsilon; 24 | Geometric2DCollection obstacles; 25 | Geometric2DCollection robot; 26 | AABB2D domain; 27 | }; 28 | 29 | #endif 30 | -------------------------------------------------------------------------------- /planning/RigidRobot3DCSpace.h: -------------------------------------------------------------------------------- 1 | #ifndef RIGID_ROBOT_2D_CSPACE_H 2 | #define RIGID_ROBOT_2D_CSPACE_H 3 | 4 | #include 5 | #include "RigidBodyCSpace.h" 6 | 7 | /** @ingroup Planning 8 | * @brief a translating and rotating 3D robot in a 3D workspace. 9 | * 10 | * Not implemented yet. 11 | */ 12 | class RigidRobot3DCSpace : public SE3CSpace 13 | { 14 | public: 15 | RigidRobot3DCSpace(); 16 | void DrawWorkspaceGL() const; 17 | void DrawRobotGL(const Config& q) const; 18 | void DrawGL(const Config& q) const; 19 | 20 | virtual int NumObstacles(); 21 | virtual std::string ObstacleName(int obstacle); 22 | virtual bool IsFeasible(const Config& x); 23 | virtual bool IsFeasible(const Config& x,int obstacle); 24 | virtual EdgePlannerPtr PathChecker(const InterpolatorPtr& path); 25 | virtual EdgePlannerPtr PathChecker(const InterpolatorPtr& path,int obstacle); 26 | virtual void Properties(PropertyMap&) const; 27 | 28 | std::vector obstacles; 29 | Geometry::AnyCollisionGeometry3D robot; 30 | }; 31 | 32 | #endif 33 | -------------------------------------------------------------------------------- /planning/SteeringFunction.h: -------------------------------------------------------------------------------- 1 | #ifndef PLANNING_STEERING_FUNCTION_H 2 | #define PLANNING_STEERING_FUNCTION_H 3 | 4 | #include "ControlSpace.h" 5 | 6 | 7 | #endif -------------------------------------------------------------------------------- /planning/TranslatingRobot2DCSpace.h: -------------------------------------------------------------------------------- 1 | #ifndef TRANSLATING_ROBOT_2D_CSPACE_H 2 | #define TRANSLATING_ROBOT_2D_CSPACE_H 3 | 4 | #include "Geometric2DCSpace.h" 5 | #include "CSpaceHelpers.h" 6 | 7 | /** @brief a translating 2D robot in a 2D workspace. 8 | */ 9 | class TranslatingRobot2DCSpace : public BoxCSpace 10 | { 11 | public: 12 | TranslatingRobot2DCSpace(); 13 | void InitConstraints(); 14 | void DrawWorkspaceGL() const; 15 | void DrawRobotGL(const Config& x) const; 16 | void DrawGL(const Config& q) const; 17 | 18 | virtual EdgePlannerPtr PathChecker(const Config& a,const Config& b) override; 19 | virtual EdgePlannerPtr PathChecker(const Config& a,const Config& b,int obstacle) override; 20 | 21 | Real visibilityEpsilon; 22 | Geometric2DCollection obstacles; 23 | Geometric2DCollection robot; 24 | AABB2D domain; 25 | }; 26 | 27 | #endif 28 | -------------------------------------------------------------------------------- /planning/VisibilityGraphPlanner.h: -------------------------------------------------------------------------------- 1 | #ifndef VISIBILITY_GRAPH_PLANNER_H 2 | #define VISIBILITY_GRAPH_PLANNER_H 3 | 4 | #include "Geometric2DCSpace.h" 5 | #include "Path.h" 6 | #include 7 | 8 | struct VisibilityGraphPlanner 9 | { 10 | VisibilityGraphPlanner(Geometric2DCSpace* space); 11 | void Init(); 12 | bool Plan(const Vector2& a,const Vector2& b,std::vector& path); 13 | bool Plan(const Config& a,const Config& b,MilestonePath& path); 14 | Real Distance(const Vector2& a,const Vector2& b); 15 | Real Distance(const Config& a,const Config& b); 16 | void AllDistances(const Vector2& a,vector& distances); 17 | void AllDistances(const Config& a,vector& distances); 18 | 19 | struct Vertex { 20 | enum Type { Endpoint, AABB, Triangle, Circle }; 21 | Type type; 22 | int obj; 23 | int idata; 24 | Real fdata; 25 | Config q; 26 | }; 27 | 28 | int TestAndConnectVertex(const Vertex& v); 29 | 30 | Geometric2DCSpace* space; 31 | Real offset; //offset from obstacle boundaries 32 | Graph::UndirectedGraph vertexGraph; 33 | Graph::UndirectedGraph tempGraph; 34 | }; 35 | 36 | 37 | #endif 38 | -------------------------------------------------------------------------------- /robotics/Chain.h: -------------------------------------------------------------------------------- 1 | #ifndef ROBOTICS_CHAIN_H 2 | #define ROBOTICS_CHAIN_H 3 | 4 | #include 5 | 6 | /** @defgroup Kinematics 7 | * @brief Classes to define robot kinematics. 8 | */ 9 | 10 | /** @ingroup Kinematics 11 | * @brief A tree-based chain structure. 12 | * 13 | * Represents the tree as a topologically sorted list of parents. 14 | * -1 represents no parent. 15 | */ 16 | class Chain 17 | { 18 | public: 19 | enum { NoParent = -1 }; 20 | 21 | bool HasValidOrdering() const; 22 | /// Returns true if p is an ancestor of n 23 | bool IsAncestor(int n, int p) const; 24 | /// Returns true if c is a descendant of n 25 | inline bool IsDescendent(int n, int c) const { return IsAncestor(c,n);} 26 | /// Least common ancestor 27 | int LCA(int a,int b) const; 28 | /// Returns a vector where element i is a vectors of the children of link i 29 | void GetChildList(std::vector >& children) const; 30 | /// Returns a vector where element i is true if it is an ancestor of n 31 | void GetAncestors(int k,std::vector& ancestors) const; 32 | /// Returns a vector where element i is true if it is an descendant of n 33 | void GetDescendants(int k,std::vector& descendants) const; 34 | 35 | /// Topologically sorted list of parents 36 | std::vector parents; 37 | }; 38 | 39 | #endif 40 | -------------------------------------------------------------------------------- /robotics/DenavitHartenberg.h: -------------------------------------------------------------------------------- 1 | #ifndef DENAVIT_HARTENBERG_H 2 | #define DENAVIT_HARTENBERG_H 3 | 4 | #include "RobotKinematics3D.h" 5 | 6 | ///Alpha and theta given in radians 7 | Math3D::RigidTransform DenavitHartenbergTransform(Real alpha,Real a,Real d,Real theta=0); 8 | 9 | ///Set up the frames and revolute axes for the robot, given the DH parameters 10 | void DenavitHartenbergRobotSetup(const std::vector& alpha,const std::vector& a,const std::vector& d,const std::vector& theta,RobotKinematics3D& robot); 11 | 12 | 13 | #endif 14 | -------------------------------------------------------------------------------- /robotics/Kinematics.h: -------------------------------------------------------------------------------- 1 | #ifndef ROBOTICS_KINEMATICS_H 2 | #define ROBOTICS_KINEMATICS_H 3 | 4 | #include "RobotKinematics3D.h" 5 | 6 | /// Returns the maximum length between the joints of link1 and link2. 7 | Real MaxJointDistance(const RobotKinematics3D&,int link1,int link2); 8 | 9 | /// Computes the matrix of maximum joint-joint distances (of the frame origins) 10 | void ComputeJointDistances(const RobotKinematics3D& robot,std::vector >& dist); 11 | 12 | /// Computes the maximal link-link distance on the robot 13 | Real MaxLimbSpan(const RobotKinematics3D& robot); 14 | 15 | #endif 16 | -------------------------------------------------------------------------------- /robotics/RLG.h: -------------------------------------------------------------------------------- 1 | #ifndef ROBOTICS_RLG_H 2 | #define ROBOTICS_RLG_H 3 | 4 | #include "JointStructure.h" 5 | 6 | /** @ingroup Kinematics 7 | * @brief A sampler for closed-chain kinematics that takes joint 8 | * workspace bounds into account. 9 | * 10 | * Analytical IK solutions can be incorporated by overloading the 11 | * SolveAnalyticalIK[X]() functions 12 | */ 13 | class RLG 14 | { 15 | public: 16 | RLG(RobotKinematics3D& robot, const JointStructure& js); 17 | void SampleFrom(int k); 18 | void Sample(const vector& ik); 19 | void Sample(const IKGoal& goal); 20 | 21 | void IterateParent(int k); 22 | void IterateChild(int k); 23 | void SampleParent(int k); 24 | void SampleChild(int k); 25 | void GetAnglesParent(int k,vector& a) const; 26 | void GetAnglesChild(int k,vector& a) const; 27 | virtual bool SolveAnalyticIKParent(int k) const { return false; } 28 | virtual bool SolveAnalyticIKChild(int k) const { return false; } 29 | 30 | RobotKinematics3D& robot; 31 | const JointStructure& js; 32 | }; 33 | 34 | /** @ingroup Kinematics 35 | * @brief RLG that sets a virtual linkage of free dof's using 36 | * analytic IK. 37 | * 38 | * Assumes joints 0-2 are rigid body translation, 3-5 rotation. 39 | */ 40 | class FreeRLG : public RLG 41 | { 42 | public: 43 | FreeRLG(RobotKinematics3D& robot, const JointStructure& js); 44 | void SampleFromRoot(); 45 | virtual bool SolveAnalyticIKParent(int k) const; 46 | }; 47 | 48 | #endif 49 | -------------------------------------------------------------------------------- /robotics/RigidBodyDynamics.h: -------------------------------------------------------------------------------- 1 | #ifndef RIGID_BODY_DYNAMICS_H 2 | #define RIGID_BODY_DYNAMICS_H 3 | 4 | #include 5 | using namespace Math3D; 6 | 7 | /** @ingroup Robotics 8 | * @brief A class for simulating a rigid body. Uses Euler integration. 9 | */ 10 | class RigidBodyDynamics 11 | { 12 | public: 13 | RigidBodyDynamics(); 14 | void SetInertiaMatrix(const Matrix3& H); 15 | void SetInertiaMatrix(const Vector3& Hdiag); 16 | void ZeroForces(); 17 | void AddForce(const Vector3& f); 18 | void AddMoment(const Vector3& m); 19 | void AddForceAtPoint(const Vector3& f,const Vector3& p); 20 | void AddLocalForceAtPoint(const Vector3& fLocal,const Vector3& pLocal); 21 | //simulate using euler integration 22 | void Advance(Real dt); 23 | 24 | //helpers 25 | Vector3 Accel() const; 26 | Vector3 AngularAccel() const; 27 | void AccelJacobian(const Vector3& forcePt,Matrix3& J) const; 28 | void AngularAccelJacobian(const Vector3& forcePt,Matrix3& J) const; 29 | Vector3 Momentum() const; 30 | Vector3 AngularMomentum() const; 31 | Matrix3 WorldInertia() const; 32 | Real KineticEnergy() const; 33 | 34 | ///Mass 35 | Real m; 36 | ///Local inertia matrix and inertia inverse 37 | Matrix3 H,Hinv; 38 | ///Transform about the COM 39 | RigidTransform T; 40 | ///World space velocity and angular velocity 41 | Vector3 v,w; 42 | 43 | //world coordinate force and moment accumulators 44 | Vector3 faccum,maccum; 45 | }; 46 | 47 | 48 | #endif 49 | -------------------------------------------------------------------------------- /robotics/SelfTest.h: -------------------------------------------------------------------------------- 1 | #ifndef ROBOTICS_SELF_TEST_H 2 | #define ROBOTICS_SELF_TEST_H 3 | 4 | #include 5 | #include 6 | 7 | void TestRotations(); 8 | void TestRLG(); 9 | void TestNewtonEuler(); 10 | 11 | #endif 12 | -------------------------------------------------------------------------------- /robotics/SolvingTorques.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/krishauser/KrisLibrary/12cae4238edfaf21c6739c9af38601b42314e14a/robotics/SolvingTorques.txt -------------------------------------------------------------------------------- /spline/MonotonicSpline.h: -------------------------------------------------------------------------------- 1 | #ifndef SPLINE_MONOTONIC_SPLINE_H 2 | #define SPLINE_MONOTONIC_SPLINE_H 3 | 4 | #include "BSpline.h" 5 | 6 | namespace Spline { 7 | 8 | /**@brief A b-spline based monotonic spline. 9 | * 10 | * Forward map: t(u), u in [0,n-1] where n=t.size() 11 | * Inverse map: u(t), u in [t[0],t[n-1]] 12 | */ 13 | struct MonotonicSpline 14 | { 15 | bool IsValid() const; 16 | Real UtoT(Real u) const; //t(u) 17 | Real TDeriv(Real u) const; //t'(u) 18 | Real TDeriv2(Real u) const; //t''(u) 19 | Real TtoU(Real time) const; //u(t) 20 | Real UDeriv(Real time) const; //u'(t) 21 | Real UDeriv2(Real time) const; //u''(t) 22 | 23 | BSplineBasis basis; 24 | std::vector t; 25 | }; 26 | 27 | } //namespace Spline 28 | 29 | #endif 30 | 31 | 32 | -------------------------------------------------------------------------------- /statistics/BetaDistribution.cpp: -------------------------------------------------------------------------------- 1 | #include "BetaDistribution.h" 2 | #include 3 | using namespace Statistics; 4 | 5 | 6 | BetaDistribution::BetaDistribution(Real _alpha,Real _beta) 7 | :alpha(_alpha),beta(_beta) 8 | {} 9 | 10 | void BetaDistribution::GetParameters(Vector& parameters) 11 | { 12 | parameters.resize(2); 13 | parameters[0]=alpha; 14 | parameters[1]=beta; 15 | } 16 | 17 | void BetaDistribution::SetParameters(const Vector& parameters) 18 | { 19 | Assert(parameters.n == 2); 20 | alpha = parameters[0]; 21 | beta = parameters[1]; 22 | } 23 | 24 | Real BetaDistribution::PDF(Real value) 25 | { 26 | if(value <= 0 || value >= 1.0) return 0; 27 | return Pow(value,alpha-One)*Pow(One-value,beta-One)/Beta(alpha,beta); 28 | } 29 | 30 | Real BetaDistribution::CDF(Real value) 31 | { 32 | return NormalizedIncompleteBeta(alpha,beta,value); 33 | } 34 | 35 | Real BetaDistribution::Mean() 36 | { 37 | return alpha/(alpha+beta); 38 | } 39 | 40 | Real BetaDistribution::Variance() 41 | { 42 | return alpha*beta/(Sqr(alpha+beta)*(alpha+beta+1.0)); 43 | } 44 | 45 | Real BetaDistribution::Skewness() 46 | { 47 | return Two*(beta-alpha)*Sqrt(alpha+beta+1)/((alpha+beta+2.0)*Sqrt(alpha*beta)); 48 | } 49 | 50 | Real BetaDistribution::Kurtosis() 51 | { 52 | Real a3=alpha*alpha*alpha; 53 | Real a2=alpha*alpha; 54 | Real a=alpha; 55 | Real b2=beta*beta; 56 | Real b=beta; 57 | return 6.0*(a3-a2*(2.0*b-1)+b2*(b+1)-2.0*a*b*(b+2.0))/(a*b*(a+b+2.0)*(a+b+3.0)); 58 | } 59 | -------------------------------------------------------------------------------- /statistics/BetaDistribution.h: -------------------------------------------------------------------------------- 1 | #ifndef BETA_DISTRIBUTION_H 2 | #define BETA_DISTRIBUTION_H 3 | 4 | #include "ProbabilityDistribution.h" 5 | #include 6 | 7 | namespace Statistics { 8 | 9 | struct BetaDistribution : public UnivariateProbabilityDistribution 10 | { 11 | BetaDistribution(Real alpha=1,Real beta=1); 12 | virtual ~BetaDistribution() {} 13 | virtual void GetParameters(Vector& parameters); 14 | virtual void SetParameters(const Vector& parameters); 15 | virtual Real PDF(Real value); 16 | virtual Real CDF(Real value); 17 | virtual Real Mean(); 18 | virtual Real Variance(); 19 | virtual Real Skewness(); 20 | virtual Real Kurtosis(); 21 | 22 | Real alpha,beta; 23 | }; 24 | 25 | } //namespace Statistics 26 | 27 | #endif 28 | -------------------------------------------------------------------------------- /statistics/DataSet.cpp: -------------------------------------------------------------------------------- 1 | #include "DataSet.h" 2 | using namespace Statistics; 3 | 4 | void DataSet::GetObservations(std::vector& output) 5 | { 6 | output.resize(0); 7 | output.resize(data.m); 8 | for(int i=0;i& input) 13 | { 14 | if(input.empty()) { 15 | data.clear(); 16 | return; 17 | } 18 | data.resize(input.size(),input[0].n); 19 | for(int i=0;i& in); 27 | void DataSet::SetObservation(int i,Vector& in); 28 | 29 | void DataSet::GetObservation(int i,std::vector& out); 30 | void DataSet::GetObservation(int i,Vector& out); 31 | 32 | void DataSet::SetElement(int j,std::vector& in); 33 | void DataSet::SetElement(int j,Vector& in); 34 | */ 35 | 36 | void DataSet::GetElement(int j,std::vector& out) 37 | { 38 | out.resize(data.m); 39 | for(int i=0;i 6 | 7 | namespace Statistics { 8 | 9 | /** @addtogroup Statistics 10 | * @brief A set of vector-valued observations. 11 | * 12 | * Internally represented as a Matrix. 13 | */ 14 | class DataSet 15 | { 16 | public: 17 | inline Real& operator()(int i,int j) { return data(i,j); } 18 | inline const Real& operator()(int i,int j) const { return data(i,j); } 19 | 20 | ///outputs the observations into the vector form. 21 | ///Note: (Vector's are references!) 22 | void GetObservations(std::vector& output); 23 | void SetObservations(const std::vector& input); 24 | 25 | ///sets the ith observation to the input vector 26 | void SetObservation(int i,std::vector& in); 27 | void SetObservation(int i,Vector& in); 28 | 29 | ///outputs the ith observation into the output vector 30 | void GetObservation(int i,std::vector& out); 31 | void GetObservation(int i,Vector& out); 32 | 33 | ///sets the jth element of data to the input vector 34 | void SetElement(int j,std::vector& in); 35 | void SetElement(int j,Vector& in); 36 | 37 | ///outputs the jth element of data into the output vector 38 | void GetElement(int j,std::vector& out); 39 | void GetElement(int j,Vector& out); 40 | 41 | std::vector labels; 42 | Matrix data; 43 | }; 44 | 45 | } 46 | 47 | #endif 48 | 49 | 50 | 51 | 52 | 53 | -------------------------------------------------------------------------------- /statistics/HierarchicalClustering.h: -------------------------------------------------------------------------------- 1 | #ifndef HIERARCHICAL_CLUSTERING_H 2 | #define HIERARCHICAL_CLUSTERING_H 3 | 4 | #include "statistics.h" 5 | 6 | namespace Statistics { 7 | 8 | class HierarchicalClustering 9 | { 10 | public: 11 | struct distances 12 | { 13 | Real dist; 14 | int index; 15 | }; 16 | 17 | // comparing operator for struct distances 18 | struct Cmp{ 19 | bool operator()(const distances d1, const distances d2) 20 | const 21 | { 22 | if(d1.dist == d2.dist) 23 | { 24 | return d1.index < d2.index; 25 | } 26 | return d1.dist < d2.dist; 27 | } 28 | }; 29 | 30 | enum Type { SingleLinkage, CompleteLinkage, AverageLinkage }; 31 | 32 | ///Builds the clustering using standard Euclidean distance 33 | void Build(const std::vector& data,int K,Type type = SingleLinkage); 34 | 35 | ///Builds the clustering for a custom distance matrix 36 | void Build(const Matrix& dist,int K,Type type = SingleLinkage); 37 | 38 | ///Returns the indices of the data elements in the i'th cluster 39 | const std::vector& Cluster(int i) const { return A[i]; } 40 | 41 | // 2d vector for storing lists of items in clusters 42 | std::vector > A; 43 | 44 | }; 45 | 46 | 47 | 48 | } //namespace Statistics 49 | 50 | #endif 51 | -------------------------------------------------------------------------------- /statistics/Histogram.h: -------------------------------------------------------------------------------- 1 | #ifndef STATISTICS_HISTOGRAM_H 2 | #define STATISTICS_HISTOGRAM_H 3 | 4 | #include "statistics.h" 5 | 6 | namespace Statistics { 7 | 8 | /** @ingroup Statistics 9 | * @brief 1-D histogram class 10 | */ 11 | class Histogram 12 | { 13 | public: 14 | Histogram(); 15 | /// Creates one big bucket 16 | void Clear(); 17 | /// Creates buckets (-inf,split],(split,inf) 18 | void Resize(Real split); 19 | /// Creates n uniformly spaced buckets betwen a,b 20 | void Resize(size_t n,Real a,Real b); 21 | /// Creates n uniformly spaced buckets between the min and max of the data 22 | void ResizeToFit(const std::vector& data,size_t n); 23 | /// Fills all buckets with the given value 24 | void Fill(Real val=0); 25 | /// Calculates the histogram of the data 26 | void Calculate(const std::vector& data); 27 | 28 | void GetRange(int bucket,Real& min,Real& max) const; 29 | int GetBucket(Real val) const; 30 | void AddBucket(Real val,Real num=1); 31 | Real GetBucketCount(int bucket) const { return buckets[bucket]; } 32 | Real NumObservations() const; 33 | 34 | std::vector divs; 35 | ///divs.size()+1 buckets (-inf,x0),[x1,x2),...,[xn-1,xn),[xn,inf) 36 | std::vector buckets; 37 | }; 38 | 39 | } //namespace Statistics 40 | 41 | #endif 42 | -------------------------------------------------------------------------------- /statistics/KMeans.h: -------------------------------------------------------------------------------- 1 | #ifndef STAT_KMEANS_H 2 | #define STAT_KMEANS_H 3 | 4 | #include 5 | #include 6 | 7 | namespace Statistics { 8 | using namespace Math; 9 | 10 | /** @ingroup Statistics 11 | * @brief A simple clustering method to choose k clusters from a set of data. 12 | * 13 | * The cluster centers are 14 | */ 15 | class KMeans 16 | { 17 | public: 18 | KMeans(const std::vector& data); 19 | KMeans(const std::vector& data,int k); 20 | virtual ~KMeans() {} 21 | int GetK() const { return (int)centers.size(); } 22 | void SetK(int k); 23 | ///Initialization 24 | void RandomInitialCenters(); 25 | void ClearLabels(); 26 | ///Returns in maxIters the number of used iterations before convergence 27 | void Iterate(int& maxIters); 28 | 29 | //Individual steps of the iteration 30 | ///Returns true if any label has changed 31 | bool CalcLabelsFromCenters(); 32 | ///Sets the centers from the data points in a center's group 33 | void CalcCentersFromLabels(); 34 | 35 | ///Returns the average distance of points for the given cluster 36 | Real AverageDistance(int c); 37 | ///Same as above, but for all clusters 38 | void AverageDistance(std::vector& dist); 39 | 40 | ///Overrideable: distance metric 41 | virtual Real Distance(const Vector& a,const Vector& b) 42 | { return a.distance(b); } 43 | 44 | const std::vector& data; 45 | const std::vector* weights; 46 | std::vector labels; 47 | std::vector centers; 48 | }; 49 | 50 | } 51 | 52 | #endif 53 | -------------------------------------------------------------------------------- /statistics/LogisticModel.h: -------------------------------------------------------------------------------- 1 | #ifndef STATISTICS_LOGISTIC_MODEL_H 2 | #define STATISTICS_LOGISTIC_MODEL_H 3 | 4 | #include "statistics.h" 5 | 6 | namespace Statistics { 7 | 8 | /** @brief Models the probability of a boolean outcome using a logit. 9 | * 10 | * The function gives p(x)=e^v/(1+e^v), where v = coeffs^t*x 11 | * The data must contain a constant term in position n. This requirement 12 | * may be relaxed in future versions 13 | */ 14 | class LogisticModel 15 | { 16 | public: 17 | LogisticModel() {} 18 | Real Evaluate(const Vector& x) const; 19 | Real EvaluateExpectation(const Vector& x,int numSamples=20) const; 20 | Real EvaluateVariance(const Vector& x,int numSamples=20) const; 21 | //calculate the maximum likelihood estimate for v[i] the boolean result 22 | //for datapoint x[i] 23 | void MaximumLikelihood(const std::vector& x,const std::vector& v,int numIters,Real tol); 24 | 25 | Vector coeffs; 26 | Matrix covariance; 27 | }; 28 | 29 | std::ostream& operator << (std::ostream& out,const LogisticModel& model); 30 | std::istream& operator >> (std::istream& in,LogisticModel& model); 31 | 32 | } //namespace Statistics 33 | 34 | #endif 35 | -------------------------------------------------------------------------------- /statistics/OnlineLASSO.h: -------------------------------------------------------------------------------- 1 | #ifndef STATISTICS_ONLINE_LASSO_H 2 | #define STATISTICS_ONLINE_LASSO_H 3 | 4 | #include "statistics.h" 5 | #include 6 | 7 | namespace Statistics { 8 | 9 | /** @brief Stochastic estimation of solution to y = A x via a LASSO-like 10 | * procedure 11 | * min_x ||b-A x||^2 + alpha*||x||_1 12 | * 13 | * The A matrix is the "data" vector, y is the "outcome" vector. 14 | * Each update step takes O(n) time, where n is the number of 15 | * dimensions in x. 16 | * 17 | * The change in coeffs is estimated each step via a LASSO-like step. It is 18 | * then added to the current estimate via the rule 19 | * x(m) = x(m-1) + w(m)*deltax(m) 20 | * where w(m) is a weight equal to 1/P(m), with P(m) being a polynomial. 21 | */ 22 | struct StochasticPseudoLASSO 23 | { 24 | StochasticPseudoLASSO(Real alpha=0.01); 25 | void SetPrior(const Vector& coeffs,int strength); 26 | void AddPoint(const Vector& data,Real outcome); 27 | 28 | Real alpha; 29 | int numObservations; 30 | std::vector weightPolynomial; 31 | Vector coeffs; //stores estimate of coeffs 32 | }; 33 | 34 | } //namespace Statistics 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /statistics/OnlineMoments.cpp: -------------------------------------------------------------------------------- 1 | #include "OnlineMoments.h" 2 | using namespace Statistics; 3 | 4 | 5 | OnlineMoments::OnlineMoments() 6 | :sumWeight(0.0) 7 | {} 8 | 9 | void AddOuterProduct(Matrix& A,const Vector& u,const Vector& v,Real w) 10 | { 11 | assert(A.m==u.n); 12 | assert(A.n==v.n); 13 | for(int i=0;i= 0); 21 | if(weight == 0) return; 22 | if(sumWeight == 0.0) { 23 | xmin = x; 24 | xmax = x; 25 | mean = x; 26 | cov.resize(x.n,x.n); 27 | cov.setZero(); 28 | sumWeight = weight; 29 | return; 30 | } 31 | assert(x.n == xmin.n); 32 | for(int i=0;i 2 | 3 | struct WeibullDistribution : public UnivariateProbabilityDistribution 4 | { 5 | WeibullDistribution(Real _a,Real _b):a(_a),b(_b) {} 6 | virtual void GetParameters(Vector& parameters) { 7 | parameters.resize(2); 8 | parameters(0)=a; 9 | parameters(1)=b; 10 | } 11 | virtual void SetParameters(const Vector& parameters) { 12 | Assert(parameters.n==2); 13 | a=parameters(0); 14 | b=parameters(1); 15 | } 16 | virtual Real PDF(Real value) { 17 | return (b/a)*Pow(value/a,b-1)*Exp(-Pow(value/a,b)); 18 | } 19 | virtual Real CDF(Real value) { 20 | return 1.0 - Exp(-Pow(value/a,b)); 21 | } 22 | virtual Real Minimum() { return 0; } 23 | virtual Real Maximum() { return Inf; } 24 | virtual Real Mean() { return a*Gamma(1.0+1.0/b); } 25 | virtual Real Median() { return a*Pow(Log2,1.0/b); } 26 | virtual Real Variance() { 27 | return Sqr(a)*Gamma(1.0+2.0/b)-Sqr(Expectation()); 28 | } 29 | virtual Real Skewness() { 30 | Real s = StandardDeviation(); 31 | Real mu = Mean(); 32 | return (Gamma(1.0+3.0/b)*a*a*a - 3.0*mu*Sqr(s) - mu*mu*mu)/(s*s*s); 33 | } 34 | virtual Real Sample() { 35 | Real x=Rand(); 36 | return Pow(-Log(1.0-x)/a,1.0/b); 37 | } 38 | virtual Real CanSample() const { return true; } 39 | 40 | Real a,b; 41 | }; 42 | 43 | -------------------------------------------------------------------------------- /utils/ContextStack.h: -------------------------------------------------------------------------------- 1 | #ifndef UTILS_CONTEXT_STACK_H 2 | #define UTILS_CONTEXT_STACK_H 3 | 4 | #include 5 | #include 6 | #include 7 | 8 | /** @brief A helper for maintaining and printing context. 9 | * 10 | * A context frame is pushed (with a name) when it is entered, and popped 11 | * when it is exited. The string cast operator returns the context string, 12 | * where the name of each frame is delimited with delim (default ':'). 13 | */ 14 | class ContextStack 15 | { 16 | public: 17 | void Push(const std::string& item) { 18 | frames.push_back(item); 19 | str += delim; 20 | str += item; 21 | } 22 | void Pop() { 23 | frames.erase(--frames.end()); 24 | str.clear(); 25 | for(std::list::const_iterator i=frames.begin();i!=frames.end();i++) { 26 | if(i!=frames.begin()) str+=delim; 27 | str += *i; 28 | } 29 | } 30 | const std::string& GetLocal() const { return frames.back(); } 31 | operator const std::string& () const { return str; } 32 | 33 | private: 34 | char delim; 35 | std::list frames; 36 | std::string str; 37 | }; 38 | 39 | #endif 40 | -------------------------------------------------------------------------------- /utils/CoverSet.h: -------------------------------------------------------------------------------- 1 | #ifndef UTIL_MUXSET_H 2 | #define UTIL_MUXSET_H 3 | 4 | #include 5 | using namespace std; 6 | 7 | /** @ingroup Utils 8 | * @brief Calculate a minimal subset of items that has a non-empty 9 | * intersection with each of the given sets. 10 | * 11 | * Each bit vector in the sets vector marks whether or 12 | * not an item is included. 13 | * 14 | * The greedy/incremental algorithm is an approximation algorithm, 15 | * with degree of approximation H(s) where s is the number 16 | * of subsets, and H is the harmonic number. 17 | */ 18 | vector CalculateCoverset_BruteForce(const vector >& sets); 19 | vector CalculateCoverset_Incremental(const vector >& sets); 20 | vector CalculateCoverset_IncrementalSorted(const vector >& sets); 21 | vector CalculateCoverset_Greedy(const vector >& sets); 22 | 23 | /** @ingroup Utils 24 | * @brief Picks the smallest subset of the given sets that 25 | * covers the whole space. 26 | * 27 | * Each bit vector in the sets vector marks whether or 28 | * not an item is included. 29 | * 30 | * Very similar to the coverset problem. 31 | * 32 | * The greedy algorithm is an approximation algorithm, 33 | * with degree of approximation H(s) where s is the number 34 | * of subsets is the harmonic number. 35 | */ 36 | vector CalculateSetCover_Greedy(const vector >& sets); 37 | 38 | 39 | #endif 40 | -------------------------------------------------------------------------------- /utils/DirtyData.h: -------------------------------------------------------------------------------- 1 | #ifndef DIRTY_DATA_H 2 | #define DIRTY_DATA_H 3 | 4 | template 5 | struct DirtyData : public type 6 | { 7 | DirtyData() : dirty(true) {} 8 | DirtyData(const type& t) : type(t),dirty(true) {} 9 | 10 | bool dirty; 11 | }; 12 | 13 | #endif 14 | -------------------------------------------------------------------------------- /utils/EZTrace.h: -------------------------------------------------------------------------------- 1 | #ifndef UTILS_EZTRACE_H 2 | #define UTILS_EZTRACE_H 3 | 4 | #include "Trace.h" 5 | #include 6 | 7 | /** @ingroup Utils 8 | * @brief A Trace that dumps on destruction. Only one may be active at 9 | * any time. 10 | * 11 | * All EZCallTrace functions log to the current trace. 12 | */ 13 | struct EZTrace 14 | { 15 | EZTrace(); 16 | ~EZTrace(); 17 | 18 | bool dumpStats,dumpTrace; 19 | Trace myTrace; 20 | 21 | static Trace* curTrace; 22 | }; 23 | 24 | /** @ingroup Utils 25 | * @brief Helper class that eases function call tracing 26 | * 27 | * On entry to a function, instantiate an EZCallTrace object. 28 | * On exit, optionally pass the return value to Return(). 29 | * If this isn't done, "void" is passed to EZTrace as the 30 | * return value. 31 | * e.g. 32 | * 33 | * int foo() { 34 | * EZCallTrace tr("foo"); 35 | * ... 36 | * return tr.Return(bar); 37 | * } 38 | */ 39 | struct EZCallTrace 40 | { 41 | EZCallTrace(const char* name); 42 | EZCallTrace(const char* name,const char* args,...); 43 | ~EZCallTrace(); 44 | 45 | template 46 | const T& Return(const T& val) { 47 | std::stringstream ss; 48 | ss<& probabilities) { 11 | sump.resize(probabilities.size()); 12 | double sum=0; 13 | for(size_t i=0;i 20 | int Sample(RNG& rng) const { 21 | double val = rng.randDouble(sump.back()); 22 | return Pick(val); 23 | } 24 | 25 | inline int Pick(double val) const { 26 | std::vector::const_iterator i=std::upper_bound(sump.begin(),sump.end(),val); 27 | return (i-sump.begin())-1; 28 | } 29 | 30 | //partial sums over probabilities 31 | std::vector sump; 32 | }; 33 | 34 | #endif 35 | -------------------------------------------------------------------------------- /utils/IndexSet.cpp: -------------------------------------------------------------------------------- 1 | #include "IndexSet.h" 2 | #include 3 | using namespace std; 4 | 5 | IndexSet::IndexSet(int _imax) 6 | :imin(0),imax(_imax) 7 | {} 8 | 9 | IndexSet::IndexSet(int _imin,int _imax) 10 | :imin(_imin),imax(_imax) 11 | {} 12 | 13 | IndexSet::IndexSet(const std::vector& _indices) 14 | :imin(0),imax(-1),indices(_indices) 15 | {} 16 | 17 | IndexSet::operator std::vector () const 18 | { 19 | if(IsRange()) { 20 | vector res(Size()); 21 | for(size_t i=0;i= imax) return -1; 46 | return i-imin; 47 | } 48 | else { 49 | for(size_t k=0;k 3 | 4 | std::ostream& operator << (std::ostream& out,const IntPair& t) 5 | { 6 | out<> (std::istream& in,IntPair& t) 11 | { 12 | in >> t.a >> t.b ; 13 | return in; 14 | } 15 | -------------------------------------------------------------------------------- /utils/IntPair.h: -------------------------------------------------------------------------------- 1 | #ifndef INT_PAIR_H 2 | #define INT_PAIR_H 3 | 4 | #include 5 | 6 | /** @ingroup Utils 7 | * @brief A lightweight integer 2-tuple class 8 | */ 9 | struct IntPair 10 | { 11 | inline IntPair() {} 12 | inline IntPair(int _a,int _b) :a(_a),b(_b) {} 13 | inline IntPair(const IntPair& t) :a(t.a),b(t.b) {} 14 | inline bool operator == (const IntPair& t) const 15 | { return a==t.a&&b==t.b; } 16 | inline bool operator != (const IntPair& t) const { return !operator==(t); } 17 | inline bool operator < (const IntPair& t) const 18 | { return a=0); 30 | } 31 | inline int count(int x) const { 32 | int n=0; 33 | for(int i=0;i<2;i++) if(x==data[i]) n++; 34 | return n; 35 | } 36 | inline void operator += (int ofs) { a+=ofs; b+=ofs; } 37 | inline void operator -= (int ofs) { a-=ofs; b-=ofs; } 38 | 39 | union { 40 | int data[2]; 41 | struct { int a,b; }; 42 | }; 43 | }; 44 | 45 | std::ostream& operator << (std::ostream& out,const IntPair& t); 46 | std::istream& operator >> (std::istream& in,IntPair& t); 47 | 48 | #endif 49 | -------------------------------------------------------------------------------- /utils/IntTriple.cpp: -------------------------------------------------------------------------------- 1 | #include "IntTriple.h" 2 | #include 3 | 4 | std::ostream& operator << (std::ostream& out,const IntTriple& t) 5 | { 6 | out<> (std::istream& in,IntTriple& t) 11 | { 12 | in >> t.a >> t.b >> t.c; 13 | return in; 14 | } 15 | -------------------------------------------------------------------------------- /utils/ParamList.h: -------------------------------------------------------------------------------- 1 | #ifndef PARAM_LIST_H 2 | #define PARAM_LIST_H 3 | 4 | #include "PrimitiveValue.h" 5 | #include 6 | #include 7 | #include 8 | 9 | struct ParamList 10 | { 11 | ParamList(); 12 | ParamList(const PrimitiveValue& a1); 13 | ParamList(const PrimitiveValue& a1,const PrimitiveValue& a2); 14 | ParamList(const PrimitiveValue& a1,const PrimitiveValue& a2,const PrimitiveValue& a3); 15 | ParamList(const PrimitiveValue& a1,const PrimitiveValue& a2,const PrimitiveValue& a3,const PrimitiveValue& a4); 16 | ParamList(const std::vector& args); 17 | ParamList(const std::map& args); 18 | bool parse(const string& str); 19 | string write() const; 20 | inline size_t size() const { return args.size(); } 21 | inline bool empty() const { return args.empty(); } 22 | inline void clear() { args.clear(); names.clear(); } 23 | inline bool contains(const std::string& name) const { return names.find(name) != names.end(); } 24 | inline PrimitiveValue& operator [] (int index) { return args[index]; } 25 | inline const PrimitiveValue& operator [] (int index) const { return args[index]; } 26 | PrimitiveValue& operator [] (const std::string& name); 27 | const PrimitiveValue& operator [] (const std::string& name) const; 28 | 29 | std::vector args; 30 | std::map names; 31 | }; 32 | 33 | #endif 34 | -------------------------------------------------------------------------------- /utils/ProgressPrinter.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "ProgressPrinter.h" 3 | #include 4 | #include 5 | using namespace std; 6 | 7 | ProgressPrinter::ProgressPrinter(ostream& _out,int _max,int _increments) 8 | :out(_out),max(_max),increments(_increments),iter(0) 9 | { 10 | } 11 | 12 | ProgressPrinter::ProgressPrinter(int _max,int _increments) 13 | :out(cout),max(_max),increments(_increments),iter(0) 14 | { 15 | } 16 | 17 | void ProgressPrinter::Update() 18 | { 19 | Update(iter+1); 20 | } 21 | 22 | void ProgressPrinter::Update(int _iter) 23 | { 24 | iter=_iter; 25 | if((iter*increments) / max != ((iter-1)*increments) / max) { 26 | Print(float(iter)/float(max)); 27 | } 28 | } 29 | 30 | void ProgressPrinter::Done() 31 | { 32 | iter=0; 33 | out<<"100%"< 5 | #include 6 | 7 | /** @ingroup Utils 8 | * @brief Prints the progress of an iterative, long computation. 9 | * 10 | * The user calls Update() each iteration from 0...max. 11 | * Print() is called "increments" times at evenly-spaced 12 | * intervals. By default, prints the percentage complete to 13 | * "out" 14 | */ 15 | class ProgressPrinter 16 | { 17 | public: 18 | ProgressPrinter(std::ostream& out,int max,int increments=100); 19 | ProgressPrinter(int max,int increments=100); 20 | void Update(); 21 | void Update(int iter); 22 | virtual void Print(float fraction); 23 | virtual void Done(); 24 | 25 | std::ostream& out; 26 | int max; 27 | int increments; 28 | int iter; 29 | }; 30 | 31 | #endif 32 | -------------------------------------------------------------------------------- /utils/SignalHandler.h: -------------------------------------------------------------------------------- 1 | #ifndef UTILS_SIGNAL_HANDLER_H 2 | #define UTILS_SIGNAL_HANDLER_H 3 | 4 | /** @ingroup Utils 5 | * @brief A base class for an object-oriented signal handler. 6 | * Properly restores old signal handlers once the class is destroyed. 7 | * 8 | * Override the OnRaise() member in your subclass. 9 | * 10 | * Set handler for a signal number with SetCurrent, unset it with 11 | * UnsetCurrent. 12 | */ 13 | class SignalHandler 14 | { 15 | public: 16 | virtual ~SignalHandler(); 17 | 18 | void SetCurrent(int signum); 19 | bool IsCurrent(int signum) const; 20 | void UnsetCurrent(int signum); 21 | static SignalHandler* GetCurrent(int signum); 22 | 23 | virtual void OnRaise(int signum)=0; 24 | }; 25 | 26 | 27 | #endif 28 | -------------------------------------------------------------------------------- /utils/apputils.h: -------------------------------------------------------------------------------- 1 | #ifndef UTILS_APPUTILS_H 2 | #define UTILS_APPUTILS_H 3 | 4 | #include "AnyCollection.h" 5 | 6 | namespace AppUtils { 7 | 8 | ///Returns a cross-platform location for saving application data 9 | std::string GetApplicationDataPath(const char* applicationName,const char* version=NULL); 10 | 11 | ///A convenience class for reading/writing settings to the application data 12 | ///folder 13 | class ProgramSettings : public AnyCollection 14 | { 15 | public: 16 | ProgramSettings(const char* applicationName,const char* version=""); 17 | bool read(const char* fn); 18 | bool write(const char* fn); 19 | std::string applicationName; 20 | std::string version; 21 | }; 22 | 23 | } //namespace AppUtils 24 | 25 | #endif 26 | -------------------------------------------------------------------------------- /utils/cmp_func.h: -------------------------------------------------------------------------------- 1 | #ifndef UTILS_CMP_FUNC_H 2 | #define UTILS_CMP_FUNC_H 3 | 4 | #include 5 | 6 | namespace std { 7 | 8 | /** @ingroup Utils 9 | * @brief A templated function class like strcmp: 10 | * returns -1 if ab. 11 | */ 12 | template > 13 | struct cmp_func 14 | { 15 | int operator()(const T& a,const T& b) { 16 | if(lessFunc(a,b)) return -1; 17 | else if(lessFunc(b,a)) return 1; 18 | return 0; 19 | } 20 | Less lessFunc; 21 | }; 22 | 23 | } //namespace std 24 | 25 | #endif 26 | -------------------------------------------------------------------------------- /utils/iteratorutils.h: -------------------------------------------------------------------------------- 1 | #ifndef ITERATOR_UTILS_H 2 | #define ITERATOR_UTILS_H 3 | 4 | /** @file utils/iteratorutils.h 5 | * @ingroup Utils 6 | * @brief Provides basic utilities to increment/decrement an 7 | * iterator by a certain amount, 2D range iterators, etc. 8 | */ 9 | 10 | /** @addtogroup Utils */ 11 | /*@{*/ 12 | 13 | template 14 | inline T increment(const T& a,int n=1) 15 | { 16 | T x=a; 17 | for(int i=0;i 22 | inline T decrement(const T& a,int n=1) 23 | { 24 | T x=a; 25 | for(int i=0;i 31 | inline int iterator_diff(const T& a,const T& b) 32 | { 33 | T x=b; 34 | int n=0; 35 | while(x!=a) { ++x; ++n; } 36 | return n; 37 | } 38 | 39 | /*@}*/ 40 | 41 | #endif 42 | -------------------------------------------------------------------------------- /utils/shift.h: -------------------------------------------------------------------------------- 1 | #ifndef UTILS_SHIFT_H 2 | #define UTILS_SHIFT_H 3 | 4 | #include 5 | 6 | /** @file utils/shift.h 7 | * @ingroup Utils 8 | * @brief Cyclical shifts of array elements 9 | */ 10 | 11 | /** @addtogroup Utils */ 12 | /*@{*/ 13 | 14 | ///Shift forward: set a'=c,b'=a,c'=b 15 | template 16 | void ShiftForward(T& a, T& b, T& c) 17 | { 18 | T temp=c; 19 | c=b; 20 | b=a; 21 | a=temp; 22 | } 23 | 24 | ///Shift backward: set a'=b,b'=c,c'=a 25 | template 26 | void ShiftBackward(T& a, T& b, T& c) 27 | { 28 | T temp=a; 29 | a=b; 30 | b=c; 31 | c=temp; 32 | } 33 | 34 | ///For all i, v'[i] = v[i-1], v'[0] = v[n-1] 35 | template 36 | void ShiftForward(std::vector& v) 37 | { 38 | if(v.empty()) return; 39 | T temp=v.back(); 40 | std::vector::iterator i,prev; 41 | for(i=--v.end();i!=v.begin();i--) { 42 | prev=i; prev--; 43 | *i = *prev; 44 | } 45 | v.front()=temp; 46 | } 47 | 48 | ///For all i, v'[i] = v[i+1], v'[n-1] = v[0] 49 | template 50 | void ShiftBackward(std::vector& v) 51 | { 52 | if(v.empty()) return; 53 | T temp=v.front(); 54 | std::vector::iterator i,next; 55 | for(i=v.begin();next!=--v.end();i++) { 56 | next=i; next++; 57 | *i = *next; 58 | } 59 | v.back()=temp; 60 | } 61 | 62 | /*@}*/ 63 | 64 | #endif 65 | -------------------------------------------------------------------------------- /utils/threadutils.cpp: -------------------------------------------------------------------------------- 1 | #include "threadutils.h" 2 | 3 | #ifdef WIN32 4 | #define WIN32_LEAN_AND_MEAN 5 | #include 6 | void ThreadSleep(double duration) { Sleep(int(duration*1000)); } 7 | #endif --------------------------------------------------------------------------------