├── .gitignore ├── .pre-commit-config.yaml ├── .pylintrc ├── .readthedocs.yaml ├── README.md ├── data ├── camera_mount.STL ├── demo_policy │ ├── stair_distill │ │ ├── config.yaml │ │ └── model_29.pt │ └── stair_rl │ │ ├── config.yaml │ │ └── model_8000.pt ├── go1 │ ├── meshes │ │ ├── calf.dae │ │ ├── calf.stl │ │ ├── depthCamera.dae │ │ ├── hip.dae │ │ ├── hip.stl │ │ ├── thigh.dae │ │ ├── thigh.stl │ │ ├── thigh_mirror.dae │ │ ├── thigh_mirror.stl │ │ ├── trunk.stl │ │ └── ultraSound.dae │ └── urdf │ │ └── go1.urdf └── mac_mini_mount.stl ├── deploy_requirements.txt ├── docs ├── Makefile ├── requirements.txt └── source │ ├── conf.py │ ├── images │ ├── block_diagram_simplified.png │ ├── camera_mount.png │ ├── dog_tracer.gif │ ├── hardware_setup.JPEG │ ├── jumping_cod.jpg │ ├── mac_mini_mount.png │ ├── motor_calibration.gif │ ├── teaser.gif │ └── teaser_stepstone.gif │ ├── index.rst │ ├── real_robot_setup.rst │ ├── simulation_setup.rst │ ├── training_a_new_policy.rst │ └── utilities.rst ├── pytype.cfg ├── requirements.txt ├── rsl_rl ├── .gitignore ├── LICENSE ├── README.md ├── licenses │ └── dependencies │ │ ├── numpy_license.txt │ │ └── torch_license.txt ├── rsl_rl │ ├── __init__.py │ ├── algorithms │ │ ├── __init__.py │ │ └── ppo.py │ ├── env │ │ ├── __init__.py │ │ └── vec_env.py │ ├── modules │ │ ├── __init__.py │ │ ├── actor_critic.py │ │ └── actor_critic_recurrent.py │ ├── runners │ │ ├── __init__.py │ │ └── on_policy_runner.py │ ├── storage │ │ ├── __init__.py │ │ └── rollout_storage.py │ └── utils │ │ ├── __init__.py │ │ └── utils.py └── setup.py ├── src ├── __init__.py ├── agents │ ├── __init__.py │ ├── heightmap_prediction │ │ ├── __init__.py │ │ ├── configs │ │ │ └── lstm_heightmap.py │ │ ├── eval.py │ │ ├── eval_real.py │ │ ├── lstm_heightmap_predictor.py │ │ ├── replay_buffer.py │ │ └── train_dagger.py │ └── ppo │ │ ├── __init__.py │ │ ├── configs │ │ ├── bound_on_platform.py │ │ ├── bound_on_stair.py │ │ ├── bound_together.py │ │ ├── bound_together_e2e.py │ │ ├── bound_together_noswingref.py │ │ ├── bound_together_speed.py │ │ ├── go1_single_jump_bound.py │ │ ├── go1_single_jump_pronk.py │ │ ├── trot_together.py │ │ └── trot_together_speed.py │ │ ├── eval.py │ │ ├── replay_actions.py │ │ └── train.py ├── configs │ ├── __init__.py │ ├── defaults │ │ ├── __init__.py │ │ ├── asset_options.py │ │ ├── go1_camera_config.py │ │ └── sim_config.py │ ├── perception.launch │ └── supervisord.conf ├── controllers │ ├── centroidal_body_controller_example.py │ ├── centroidal_body_controller_stand_example.py │ ├── phase_gait_generator.py │ ├── phase_gait_generator_example.py │ ├── qp_torque_optimizer.py │ ├── qp_torque_optimizer_numpy.py.bak │ └── raibert_swing_leg_controller.py ├── envs │ ├── configs │ │ └── bound_together.py │ ├── env_wrappers.py │ ├── go1_rewards.py │ ├── jump_env.py │ └── terrain.py ├── robots │ ├── __init__.py │ ├── gamepad_reader.py │ ├── go1.py │ ├── go1_robot.py │ ├── go1_robot_exercise_example.py │ ├── motors.py │ ├── realsense_image_capture.py │ ├── robot.py │ └── robot_state_estimator.py └── utils │ ├── __init__.py │ ├── dog_tracer │ ├── assets │ │ └── app.css │ ├── dog_tracer.py │ └── video_generator_example.py │ ├── go1_camera_calibration.py │ ├── go1_camera_calibration_sim.py │ ├── go1_motor_calibration.py │ ├── moving_window_filter.py │ ├── pilots_eye │ ├── __init__.py │ ├── assets │ │ └── img │ │ │ └── placeholder.png │ ├── index.html │ ├── pilots_eye.py │ └── scripts │ │ ├── eventemitter2.min.js │ │ └── roslib.min.js │ └── torch_utils.py └── third_party ├── eigen3 ├── .DS_Store └── include │ ├── Eigen │ ├── Cholesky │ ├── CholmodSupport │ ├── Core │ ├── Dense │ ├── Eigen │ ├── Eigenvalues │ ├── Geometry │ ├── Householder │ ├── IterativeLinearSolvers │ ├── Jacobi │ ├── KLUSupport │ ├── LU │ ├── MetisSupport │ ├── OrderingMethods │ ├── PaStiXSupport │ ├── PardisoSupport │ ├── QR │ ├── QtAlignedMalloc │ ├── SPQRSupport │ ├── SVD │ ├── Sparse │ ├── SparseCholesky │ ├── SparseCore │ ├── SparseLU │ ├── SparseQR │ ├── StdDeque │ ├── StdList │ ├── StdVector │ ├── SuperLUSupport │ ├── UmfPackSupport │ └── src │ │ ├── Cholesky │ │ ├── LDLT.h │ │ ├── LLT.h │ │ └── LLT_LAPACKE.h │ │ ├── CholmodSupport │ │ └── CholmodSupport.h │ │ ├── Core │ │ ├── ArithmeticSequence.h │ │ ├── Array.h │ │ ├── ArrayBase.h │ │ ├── ArrayWrapper.h │ │ ├── Assign.h │ │ ├── AssignEvaluator.h │ │ ├── Assign_MKL.h │ │ ├── BandMatrix.h │ │ ├── Block.h │ │ ├── BooleanRedux.h │ │ ├── CommaInitializer.h │ │ ├── ConditionEstimator.h │ │ ├── CoreEvaluators.h │ │ ├── CoreIterators.h │ │ ├── CwiseBinaryOp.h │ │ ├── CwiseNullaryOp.h │ │ ├── CwiseTernaryOp.h │ │ ├── CwiseUnaryOp.h │ │ ├── CwiseUnaryView.h │ │ ├── DenseBase.h │ │ ├── DenseCoeffsBase.h │ │ ├── DenseStorage.h │ │ ├── Diagonal.h │ │ ├── DiagonalMatrix.h │ │ ├── DiagonalProduct.h │ │ ├── Dot.h │ │ ├── EigenBase.h │ │ ├── ForceAlignedAccess.h │ │ ├── Fuzzy.h │ │ ├── GeneralProduct.h │ │ ├── GenericPacketMath.h │ │ ├── GlobalFunctions.h │ │ ├── IO.h │ │ ├── IndexedView.h │ │ ├── Inverse.h │ │ ├── Map.h │ │ ├── MapBase.h │ │ ├── MathFunctions.h │ │ ├── MathFunctionsImpl.h │ │ ├── Matrix.h │ │ ├── MatrixBase.h │ │ ├── NestByValue.h │ │ ├── NoAlias.h │ │ ├── NumTraits.h │ │ ├── PartialReduxEvaluator.h │ │ ├── PermutationMatrix.h │ │ ├── PlainObjectBase.h │ │ ├── Product.h │ │ ├── ProductEvaluators.h │ │ ├── Random.h │ │ ├── Redux.h │ │ ├── Ref.h │ │ ├── Replicate.h │ │ ├── Reshaped.h │ │ ├── ReturnByValue.h │ │ ├── Reverse.h │ │ ├── Select.h │ │ ├── SelfAdjointView.h │ │ ├── SelfCwiseBinaryOp.h │ │ ├── Solve.h │ │ ├── SolveTriangular.h │ │ ├── SolverBase.h │ │ ├── StableNorm.h │ │ ├── StlIterators.h │ │ ├── Stride.h │ │ ├── Swap.h │ │ ├── Transpose.h │ │ ├── Transpositions.h │ │ ├── TriangularMatrix.h │ │ ├── VectorBlock.h │ │ ├── VectorwiseOp.h │ │ ├── Visitor.h │ │ ├── arch │ │ │ ├── AVX │ │ │ │ ├── Complex.h │ │ │ │ ├── MathFunctions.h │ │ │ │ ├── PacketMath.h │ │ │ │ └── TypeCasting.h │ │ │ ├── AVX512 │ │ │ │ ├── Complex.h │ │ │ │ ├── MathFunctions.h │ │ │ │ ├── PacketMath.h │ │ │ │ └── TypeCasting.h │ │ │ ├── AltiVec │ │ │ │ ├── Complex.h │ │ │ │ ├── MathFunctions.h │ │ │ │ ├── MatrixProduct.h │ │ │ │ └── PacketMath.h │ │ │ ├── CUDA │ │ │ │ └── Complex.h │ │ │ ├── Default │ │ │ │ ├── BFloat16.h │ │ │ │ ├── ConjHelper.h │ │ │ │ ├── GenericPacketMathFunctions.h │ │ │ │ ├── GenericPacketMathFunctionsFwd.h │ │ │ │ ├── Half.h │ │ │ │ ├── Settings.h │ │ │ │ └── TypeCasting.h │ │ │ ├── GPU │ │ │ │ ├── MathFunctions.h │ │ │ │ ├── PacketMath.h │ │ │ │ └── TypeCasting.h │ │ │ ├── HIP │ │ │ │ └── hcc │ │ │ │ │ └── math_constants.h │ │ │ ├── MSA │ │ │ │ ├── Complex.h │ │ │ │ ├── MathFunctions.h │ │ │ │ └── PacketMath.h │ │ │ ├── NEON │ │ │ │ ├── Complex.h │ │ │ │ ├── MathFunctions.h │ │ │ │ ├── PacketMath.h │ │ │ │ └── TypeCasting.h │ │ │ ├── SSE │ │ │ │ ├── Complex.h │ │ │ │ ├── MathFunctions.h │ │ │ │ ├── PacketMath.h │ │ │ │ └── TypeCasting.h │ │ │ ├── SYCL │ │ │ │ ├── InteropHeaders.h │ │ │ │ ├── MathFunctions.h │ │ │ │ ├── PacketMath.h │ │ │ │ ├── SyclMemoryModel.h │ │ │ │ └── TypeCasting.h │ │ │ └── ZVector │ │ │ │ ├── Complex.h │ │ │ │ ├── MathFunctions.h │ │ │ │ └── PacketMath.h │ │ ├── functors │ │ │ ├── AssignmentFunctors.h │ │ │ ├── BinaryFunctors.h │ │ │ ├── NullaryFunctors.h │ │ │ ├── StlFunctors.h │ │ │ ├── TernaryFunctors.h │ │ │ └── UnaryFunctors.h │ │ ├── products │ │ │ ├── GeneralBlockPanelKernel.h │ │ │ ├── GeneralMatrixMatrix.h │ │ │ ├── GeneralMatrixMatrixTriangular.h │ │ │ ├── GeneralMatrixMatrixTriangular_BLAS.h │ │ │ ├── GeneralMatrixMatrix_BLAS.h │ │ │ ├── GeneralMatrixVector.h │ │ │ ├── GeneralMatrixVector_BLAS.h │ │ │ ├── Parallelizer.h │ │ │ ├── SelfadjointMatrixMatrix.h │ │ │ ├── SelfadjointMatrixMatrix_BLAS.h │ │ │ ├── SelfadjointMatrixVector.h │ │ │ ├── SelfadjointMatrixVector_BLAS.h │ │ │ ├── SelfadjointProduct.h │ │ │ ├── SelfadjointRank2Update.h │ │ │ ├── TriangularMatrixMatrix.h │ │ │ ├── TriangularMatrixMatrix_BLAS.h │ │ │ ├── TriangularMatrixVector.h │ │ │ ├── TriangularMatrixVector_BLAS.h │ │ │ ├── TriangularSolverMatrix.h │ │ │ ├── TriangularSolverMatrix_BLAS.h │ │ │ └── TriangularSolverVector.h │ │ └── util │ │ │ ├── BlasUtil.h │ │ │ ├── ConfigureVectorization.h │ │ │ ├── Constants.h │ │ │ ├── DisableStupidWarnings.h │ │ │ ├── ForwardDeclarations.h │ │ │ ├── IndexedViewHelper.h │ │ │ ├── IntegralConstant.h │ │ │ ├── MKL_support.h │ │ │ ├── Macros.h │ │ │ ├── Memory.h │ │ │ ├── Meta.h │ │ │ ├── NonMPL2.h │ │ │ ├── ReenableStupidWarnings.h │ │ │ ├── ReshapedHelper.h │ │ │ ├── StaticAssert.h │ │ │ ├── SymbolicIndex.h │ │ │ └── XprHelper.h │ │ ├── Eigenvalues │ │ ├── ComplexEigenSolver.h │ │ ├── ComplexSchur.h │ │ ├── ComplexSchur_LAPACKE.h │ │ ├── EigenSolver.h │ │ ├── GeneralizedEigenSolver.h │ │ ├── GeneralizedSelfAdjointEigenSolver.h │ │ ├── HessenbergDecomposition.h │ │ ├── MatrixBaseEigenvalues.h │ │ ├── RealQZ.h │ │ ├── RealSchur.h │ │ ├── RealSchur_LAPACKE.h │ │ ├── SelfAdjointEigenSolver.h │ │ ├── SelfAdjointEigenSolver_LAPACKE.h │ │ └── Tridiagonalization.h │ │ ├── Geometry │ │ ├── AlignedBox.h │ │ ├── AngleAxis.h │ │ ├── EulerAngles.h │ │ ├── Homogeneous.h │ │ ├── Hyperplane.h │ │ ├── OrthoMethods.h │ │ ├── ParametrizedLine.h │ │ ├── Quaternion.h │ │ ├── Rotation2D.h │ │ ├── RotationBase.h │ │ ├── Scaling.h │ │ ├── Transform.h │ │ ├── Translation.h │ │ ├── Umeyama.h │ │ └── arch │ │ │ └── Geometry_SSE.h │ │ ├── Householder │ │ ├── BlockHouseholder.h │ │ ├── Householder.h │ │ └── HouseholderSequence.h │ │ ├── IterativeLinearSolvers │ │ ├── BasicPreconditioners.h │ │ ├── BiCGSTAB.h │ │ ├── ConjugateGradient.h │ │ ├── IncompleteCholesky.h │ │ ├── IncompleteLUT.h │ │ ├── IterativeSolverBase.h │ │ ├── LeastSquareConjugateGradient.h │ │ └── SolveWithGuess.h │ │ ├── Jacobi │ │ └── Jacobi.h │ │ ├── KLUSupport │ │ └── KLUSupport.h │ │ ├── LU │ │ ├── Determinant.h │ │ ├── FullPivLU.h │ │ ├── InverseImpl.h │ │ ├── PartialPivLU.h │ │ ├── PartialPivLU_LAPACKE.h │ │ └── arch │ │ │ └── Inverse_SSE.h │ │ ├── MetisSupport │ │ └── MetisSupport.h │ │ ├── OrderingMethods │ │ ├── Amd.h │ │ ├── Eigen_Colamd.h │ │ └── Ordering.h │ │ ├── PaStiXSupport │ │ └── PaStiXSupport.h │ │ ├── PardisoSupport │ │ └── PardisoSupport.h │ │ ├── QR │ │ ├── ColPivHouseholderQR.h │ │ ├── ColPivHouseholderQR_LAPACKE.h │ │ ├── CompleteOrthogonalDecomposition.h │ │ ├── FullPivHouseholderQR.h │ │ ├── HouseholderQR.h │ │ └── HouseholderQR_LAPACKE.h │ │ ├── SPQRSupport │ │ └── SuiteSparseQRSupport.h │ │ ├── SVD │ │ ├── BDCSVD.h │ │ ├── JacobiSVD.h │ │ ├── JacobiSVD_LAPACKE.h │ │ ├── SVDBase.h │ │ └── UpperBidiagonalization.h │ │ ├── SparseCholesky │ │ ├── SimplicialCholesky.h │ │ └── SimplicialCholesky_impl.h │ │ ├── SparseCore │ │ ├── AmbiVector.h │ │ ├── CompressedStorage.h │ │ ├── ConservativeSparseSparseProduct.h │ │ ├── MappedSparseMatrix.h │ │ ├── SparseAssign.h │ │ ├── SparseBlock.h │ │ ├── SparseColEtree.h │ │ ├── SparseCompressedBase.h │ │ ├── SparseCwiseBinaryOp.h │ │ ├── SparseCwiseUnaryOp.h │ │ ├── SparseDenseProduct.h │ │ ├── SparseDiagonalProduct.h │ │ ├── SparseDot.h │ │ ├── SparseFuzzy.h │ │ ├── SparseMap.h │ │ ├── SparseMatrix.h │ │ ├── SparseMatrixBase.h │ │ ├── SparsePermutation.h │ │ ├── SparseProduct.h │ │ ├── SparseRedux.h │ │ ├── SparseRef.h │ │ ├── SparseSelfAdjointView.h │ │ ├── SparseSolverBase.h │ │ ├── SparseSparseProductWithPruning.h │ │ ├── SparseTranspose.h │ │ ├── SparseTriangularView.h │ │ ├── SparseUtil.h │ │ ├── SparseVector.h │ │ ├── SparseView.h │ │ └── TriangularSolver.h │ │ ├── SparseLU │ │ ├── SparseLU.h │ │ ├── SparseLUImpl.h │ │ ├── SparseLU_Memory.h │ │ ├── SparseLU_Structs.h │ │ ├── SparseLU_SupernodalMatrix.h │ │ ├── SparseLU_Utils.h │ │ ├── SparseLU_column_bmod.h │ │ ├── SparseLU_column_dfs.h │ │ ├── SparseLU_copy_to_ucol.h │ │ ├── SparseLU_gemm_kernel.h │ │ ├── SparseLU_heap_relax_snode.h │ │ ├── SparseLU_kernel_bmod.h │ │ ├── SparseLU_panel_bmod.h │ │ ├── SparseLU_panel_dfs.h │ │ ├── SparseLU_pivotL.h │ │ ├── SparseLU_pruneL.h │ │ └── SparseLU_relax_snode.h │ │ ├── SparseQR │ │ └── SparseQR.h │ │ ├── StlSupport │ │ ├── StdDeque.h │ │ ├── StdList.h │ │ ├── StdVector.h │ │ └── details.h │ │ ├── SuperLUSupport │ │ └── SuperLUSupport.h │ │ ├── UmfPackSupport │ │ └── UmfPackSupport.h │ │ ├── misc │ │ ├── Image.h │ │ ├── Kernel.h │ │ ├── RealSvd2x2.h │ │ ├── blas.h │ │ ├── lapack.h │ │ ├── lapacke.h │ │ └── lapacke_mangling.h │ │ └── plugins │ │ ├── ArrayCwiseBinaryOps.h │ │ ├── ArrayCwiseUnaryOps.h │ │ ├── BlockMethods.h │ │ ├── CommonCwiseBinaryOps.h │ │ ├── CommonCwiseUnaryOps.h │ │ ├── IndexedViewMethods.h │ │ ├── MatrixCwiseBinaryOps.h │ │ ├── MatrixCwiseUnaryOps.h │ │ └── ReshapedMethods.h │ └── unsupported │ ├── CMakeLists.txt │ ├── Eigen │ ├── AdolcForward │ ├── AlignedVector3 │ ├── ArpackSupport │ ├── AutoDiff │ ├── BVH │ ├── CMakeLists.txt │ ├── CXX11 │ │ ├── CMakeLists.txt │ │ ├── Tensor │ │ ├── TensorSymmetry │ │ ├── ThreadPool │ │ └── src │ │ │ ├── Tensor │ │ │ ├── README.md │ │ │ ├── Tensor.h │ │ │ ├── TensorArgMax.h │ │ │ ├── TensorAssign.h │ │ │ ├── TensorBase.h │ │ │ ├── TensorBlock.h │ │ │ ├── TensorBroadcasting.h │ │ │ ├── TensorChipping.h │ │ │ ├── TensorConcatenation.h │ │ │ ├── TensorContraction.h │ │ │ ├── TensorContractionBlocking.h │ │ │ ├── TensorContractionCuda.h │ │ │ ├── TensorContractionGpu.h │ │ │ ├── TensorContractionMapper.h │ │ │ ├── TensorContractionSycl.h │ │ │ ├── TensorContractionThreadPool.h │ │ │ ├── TensorConversion.h │ │ │ ├── TensorConvolution.h │ │ │ ├── TensorConvolutionSycl.h │ │ │ ├── TensorCostModel.h │ │ │ ├── TensorCustomOp.h │ │ │ ├── TensorDevice.h │ │ │ ├── TensorDeviceCuda.h │ │ │ ├── TensorDeviceDefault.h │ │ │ ├── TensorDeviceGpu.h │ │ │ ├── TensorDeviceSycl.h │ │ │ ├── TensorDeviceThreadPool.h │ │ │ ├── TensorDimensionList.h │ │ │ ├── TensorDimensions.h │ │ │ ├── TensorEvalTo.h │ │ │ ├── TensorEvaluator.h │ │ │ ├── TensorExecutor.h │ │ │ ├── TensorExpr.h │ │ │ ├── TensorFFT.h │ │ │ ├── TensorFixedSize.h │ │ │ ├── TensorForcedEval.h │ │ │ ├── TensorForwardDeclarations.h │ │ │ ├── TensorFunctors.h │ │ │ ├── TensorGenerator.h │ │ │ ├── TensorGlobalFunctions.h │ │ │ ├── TensorGpuHipCudaDefines.h │ │ │ ├── TensorGpuHipCudaUndefines.h │ │ │ ├── TensorIO.h │ │ │ ├── TensorImagePatch.h │ │ │ ├── TensorIndexList.h │ │ │ ├── TensorInflation.h │ │ │ ├── TensorInitializer.h │ │ │ ├── TensorIntDiv.h │ │ │ ├── TensorLayoutSwap.h │ │ │ ├── TensorMacros.h │ │ │ ├── TensorMap.h │ │ │ ├── TensorMeta.h │ │ │ ├── TensorMorphing.h │ │ │ ├── TensorPadding.h │ │ │ ├── TensorPatch.h │ │ │ ├── TensorRandom.h │ │ │ ├── TensorReduction.h │ │ │ ├── TensorReductionCuda.h │ │ │ ├── TensorReductionGpu.h │ │ │ ├── TensorReductionSycl.h │ │ │ ├── TensorRef.h │ │ │ ├── TensorReverse.h │ │ │ ├── TensorScan.h │ │ │ ├── TensorScanSycl.h │ │ │ ├── TensorShuffling.h │ │ │ ├── TensorStorage.h │ │ │ ├── TensorStriding.h │ │ │ ├── TensorTrace.h │ │ │ ├── TensorTraits.h │ │ │ ├── TensorUInt128.h │ │ │ └── TensorVolumePatch.h │ │ │ ├── TensorSymmetry │ │ │ ├── DynamicSymmetry.h │ │ │ ├── StaticSymmetry.h │ │ │ ├── Symmetry.h │ │ │ └── util │ │ │ │ └── TemplateGroupTheory.h │ │ │ ├── ThreadPool │ │ │ ├── Barrier.h │ │ │ ├── EventCount.h │ │ │ ├── NonBlockingThreadPool.h │ │ │ ├── RunQueue.h │ │ │ ├── ThreadCancel.h │ │ │ ├── ThreadEnvironment.h │ │ │ ├── ThreadLocal.h │ │ │ ├── ThreadPoolInterface.h │ │ │ └── ThreadYield.h │ │ │ └── util │ │ │ ├── CXX11Meta.h │ │ │ ├── CXX11Workarounds.h │ │ │ ├── EmulateArray.h │ │ │ └── MaxSizeVector.h │ ├── EulerAngles │ ├── FFT │ ├── IterativeSolvers │ ├── KroneckerProduct │ ├── LevenbergMarquardt │ ├── MPRealSupport │ ├── MatrixFunctions │ ├── MoreVectorization │ ├── NonLinearOptimization │ ├── NumericalDiff │ ├── OpenGLSupport │ ├── Polynomials │ ├── Skyline │ ├── SparseExtra │ ├── SpecialFunctions │ ├── Splines │ └── src │ │ ├── AutoDiff │ │ ├── AutoDiffJacobian.h │ │ ├── AutoDiffScalar.h │ │ └── AutoDiffVector.h │ │ ├── BVH │ │ ├── BVAlgorithms.h │ │ └── KdBVH.h │ │ ├── Eigenvalues │ │ └── ArpackSelfAdjointEigenSolver.h │ │ ├── EulerAngles │ │ ├── CMakeLists.txt │ │ ├── EulerAngles.h │ │ └── EulerSystem.h │ │ ├── FFT │ │ ├── ei_fftw_impl.h │ │ └── ei_kissfft_impl.h │ │ ├── IterativeSolvers │ │ ├── ConstrainedConjGrad.h │ │ ├── DGMRES.h │ │ ├── GMRES.h │ │ ├── IncompleteLU.h │ │ ├── IterationController.h │ │ ├── MINRES.h │ │ └── Scaling.h │ │ ├── KroneckerProduct │ │ └── KroneckerTensorProduct.h │ │ ├── LevenbergMarquardt │ │ ├── CopyrightMINPACK.txt │ │ ├── LMcovar.h │ │ ├── LMonestep.h │ │ ├── LMpar.h │ │ ├── LMqrsolv.h │ │ └── LevenbergMarquardt.h │ │ ├── MatrixFunctions │ │ ├── MatrixExponential.h │ │ ├── MatrixFunction.h │ │ ├── MatrixLogarithm.h │ │ ├── MatrixPower.h │ │ ├── MatrixSquareRoot.h │ │ └── StemFunction.h │ │ ├── MoreVectorization │ │ └── MathFunctions.h │ │ ├── NonLinearOptimization │ │ ├── HybridNonLinearSolver.h │ │ ├── LevenbergMarquardt.h │ │ ├── chkder.h │ │ ├── covar.h │ │ ├── dogleg.h │ │ ├── fdjac1.h │ │ ├── lmpar.h │ │ ├── qrsolv.h │ │ ├── r1mpyq.h │ │ ├── r1updt.h │ │ └── rwupdt.h │ │ ├── NumericalDiff │ │ └── NumericalDiff.h │ │ ├── Polynomials │ │ ├── Companion.h │ │ ├── PolynomialSolver.h │ │ └── PolynomialUtils.h │ │ ├── Skyline │ │ ├── SkylineInplaceLU.h │ │ ├── SkylineMatrix.h │ │ ├── SkylineMatrixBase.h │ │ ├── SkylineProduct.h │ │ ├── SkylineStorage.h │ │ └── SkylineUtil.h │ │ ├── SparseExtra │ │ ├── BlockOfDynamicSparseMatrix.h │ │ ├── BlockSparseMatrix.h │ │ ├── DynamicSparseMatrix.h │ │ ├── MarketIO.h │ │ ├── MatrixMarketIterator.h │ │ └── RandomSetter.h │ │ ├── SpecialFunctions │ │ ├── BesselFunctionsArrayAPI.h │ │ ├── BesselFunctionsBFloat16.h │ │ ├── BesselFunctionsFunctors.h │ │ ├── BesselFunctionsHalf.h │ │ ├── BesselFunctionsImpl.h │ │ ├── BesselFunctionsPacketMath.h │ │ ├── HipVectorCompatibility.h │ │ ├── SpecialFunctionsArrayAPI.h │ │ ├── SpecialFunctionsBFloat16.h │ │ ├── SpecialFunctionsFunctors.h │ │ ├── SpecialFunctionsHalf.h │ │ ├── SpecialFunctionsImpl.h │ │ ├── SpecialFunctionsPacketMath.h │ │ └── arch │ │ │ └── GPU │ │ │ └── GpuSpecialFunctions.h │ │ └── Splines │ │ ├── Spline.h │ │ ├── SplineFitting.h │ │ └── SplineFwd.h │ ├── README.txt │ ├── bench │ └── bench_svd.cpp │ ├── doc │ ├── CMakeLists.txt │ ├── Overview.dox │ ├── SYCL.dox │ ├── eigendoxy_layout.xml.in │ ├── examples │ │ ├── BVH_Example.cpp │ │ ├── CMakeLists.txt │ │ ├── EulerAngles.cpp │ │ ├── FFT.cpp │ │ ├── MatrixExponential.cpp │ │ ├── MatrixFunction.cpp │ │ ├── MatrixLogarithm.cpp │ │ ├── MatrixPower.cpp │ │ ├── MatrixPower_optimal.cpp │ │ ├── MatrixSine.cpp │ │ ├── MatrixSinh.cpp │ │ ├── MatrixSquareRoot.cpp │ │ ├── PolynomialSolver1.cpp │ │ ├── PolynomialUtils1.cpp │ │ └── SYCL │ │ │ ├── CMakeLists.txt │ │ │ └── CwiseMul.cpp │ └── snippets │ │ └── CMakeLists.txt │ └── test │ ├── BVH.cpp │ ├── CMakeLists.txt │ ├── EulerAngles.cpp │ ├── FFT.cpp │ ├── FFTW.cpp │ ├── NonLinearOptimization.cpp │ ├── NumericalDiff.cpp │ ├── alignedvector3.cpp │ ├── autodiff.cpp │ ├── autodiff_scalar.cpp │ ├── bessel_functions.cpp │ ├── cxx11_eventcount.cpp │ ├── cxx11_maxsizevector.cpp │ ├── cxx11_meta.cpp │ ├── cxx11_non_blocking_thread_pool.cpp │ ├── cxx11_runqueue.cpp │ ├── cxx11_tensor_argmax.cpp │ ├── cxx11_tensor_argmax_gpu.cu │ ├── cxx11_tensor_argmax_sycl.cpp │ ├── cxx11_tensor_assign.cpp │ ├── cxx11_tensor_block_access.cpp │ ├── cxx11_tensor_block_eval.cpp │ ├── cxx11_tensor_block_io.cpp │ ├── cxx11_tensor_broadcast_sycl.cpp │ ├── cxx11_tensor_broadcasting.cpp │ ├── cxx11_tensor_builtins_sycl.cpp │ ├── cxx11_tensor_cast_float16_gpu.cu │ ├── cxx11_tensor_casts.cpp │ ├── cxx11_tensor_chipping.cpp │ ├── cxx11_tensor_chipping_sycl.cpp │ ├── cxx11_tensor_comparisons.cpp │ ├── cxx11_tensor_complex_cwise_ops_gpu.cu │ ├── cxx11_tensor_complex_gpu.cu │ ├── cxx11_tensor_concatenation.cpp │ ├── cxx11_tensor_concatenation_sycl.cpp │ ├── cxx11_tensor_const.cpp │ ├── cxx11_tensor_contract_gpu.cu │ ├── cxx11_tensor_contract_sycl.cpp │ ├── cxx11_tensor_contraction.cpp │ ├── cxx11_tensor_convolution.cpp │ ├── cxx11_tensor_convolution_sycl.cpp │ ├── cxx11_tensor_custom_index.cpp │ ├── cxx11_tensor_custom_op.cpp │ ├── cxx11_tensor_custom_op_sycl.cpp │ ├── cxx11_tensor_device.cu │ ├── cxx11_tensor_device_sycl.cpp │ ├── cxx11_tensor_dimension.cpp │ ├── cxx11_tensor_empty.cpp │ ├── cxx11_tensor_executor.cpp │ ├── cxx11_tensor_expr.cpp │ ├── cxx11_tensor_fft.cpp │ ├── cxx11_tensor_fixed_size.cpp │ ├── cxx11_tensor_forced_eval.cpp │ ├── cxx11_tensor_forced_eval_sycl.cpp │ ├── cxx11_tensor_generator.cpp │ ├── cxx11_tensor_generator_sycl.cpp │ ├── cxx11_tensor_gpu.cu │ ├── cxx11_tensor_ifft.cpp │ ├── cxx11_tensor_image_op_sycl.cpp │ ├── cxx11_tensor_image_patch.cpp │ ├── cxx11_tensor_image_patch_sycl.cpp │ ├── cxx11_tensor_index_list.cpp │ ├── cxx11_tensor_inflation.cpp │ ├── cxx11_tensor_inflation_sycl.cpp │ ├── cxx11_tensor_intdiv.cpp │ ├── cxx11_tensor_io.cpp │ ├── cxx11_tensor_layout_swap.cpp │ ├── cxx11_tensor_layout_swap_sycl.cpp │ ├── cxx11_tensor_lvalue.cpp │ ├── cxx11_tensor_map.cpp │ ├── cxx11_tensor_math.cpp │ ├── cxx11_tensor_math_sycl.cpp │ ├── cxx11_tensor_mixed_indices.cpp │ ├── cxx11_tensor_morphing.cpp │ ├── cxx11_tensor_morphing_sycl.cpp │ ├── cxx11_tensor_move.cpp │ ├── cxx11_tensor_notification.cpp │ ├── cxx11_tensor_of_complex.cpp │ ├── cxx11_tensor_of_const_values.cpp │ ├── cxx11_tensor_of_float16_gpu.cu │ ├── cxx11_tensor_of_strings.cpp │ ├── cxx11_tensor_padding.cpp │ ├── cxx11_tensor_padding_sycl.cpp │ ├── cxx11_tensor_patch.cpp │ ├── cxx11_tensor_patch_sycl.cpp │ ├── cxx11_tensor_random.cpp │ ├── cxx11_tensor_random_gpu.cu │ ├── cxx11_tensor_random_sycl.cpp │ ├── cxx11_tensor_reduction.cpp │ ├── cxx11_tensor_reduction_gpu.cu │ ├── cxx11_tensor_reduction_sycl.cpp │ ├── cxx11_tensor_ref.cpp │ ├── cxx11_tensor_reverse.cpp │ ├── cxx11_tensor_reverse_sycl.cpp │ ├── cxx11_tensor_roundings.cpp │ ├── cxx11_tensor_scan.cpp │ ├── cxx11_tensor_scan_gpu.cu │ ├── cxx11_tensor_scan_sycl.cpp │ ├── cxx11_tensor_shuffling.cpp │ ├── cxx11_tensor_shuffling_sycl.cpp │ ├── cxx11_tensor_simple.cpp │ ├── cxx11_tensor_striding.cpp │ ├── cxx11_tensor_striding_sycl.cpp │ ├── cxx11_tensor_sugar.cpp │ ├── cxx11_tensor_sycl.cpp │ ├── cxx11_tensor_symmetry.cpp │ ├── cxx11_tensor_thread_local.cpp │ ├── cxx11_tensor_thread_pool.cpp │ ├── cxx11_tensor_trace.cpp │ ├── cxx11_tensor_uint128.cpp │ ├── cxx11_tensor_volume_patch.cpp │ ├── cxx11_tensor_volume_patch_sycl.cpp │ ├── dgmres.cpp │ ├── forward_adolc.cpp │ ├── gmres.cpp │ ├── kronecker_product.cpp │ ├── levenberg_marquardt.cpp │ ├── matrix_exponential.cpp │ ├── matrix_function.cpp │ ├── matrix_functions.h │ ├── matrix_power.cpp │ ├── matrix_square_root.cpp │ ├── minres.cpp │ ├── mpreal │ └── mpreal.h │ ├── mpreal_support.cpp │ ├── openglsupport.cpp │ ├── polynomialsolver.cpp │ ├── polynomialutils.cpp │ ├── sparse_extra.cpp │ ├── special_functions.cpp │ ├── special_packetmath.cpp │ └── splines.cpp └── go1_sdk ├── .gitignore ├── CMakeLists.txt ├── CMakeLists_bak.txt ├── LICENSE ├── README.md ├── go1_python_interface.cpp ├── include └── unitree_legged_sdk │ ├── a1_const.h │ ├── aliengo_const.h │ ├── comm.h │ ├── go1_const.h │ ├── joystick.h │ ├── loop.h │ ├── quadruped.h │ ├── safety.h │ ├── udp.h │ └── unitree_legged_sdk.h ├── lib ├── cpp │ ├── amd64 │ │ └── libunitree_legged_sdk.a │ └── arm64 │ │ └── libunitree_legged_sdk.a └── python │ ├── amd64 │ └── robot_interface.cpython-38-x86_64-linux-gnu.so │ └── arm64 │ ├── robot_interface.cpython-37m-aarch64-linux-gnu.so │ └── robot_interface.cpython-38-aarch64-linux-gnu.so └── pybind11 ├── .appveyor.yml ├── .clang-format ├── .clang-tidy ├── .cmake-format.yaml ├── .codespell-ignore-lines ├── .gitattributes ├── .github ├── CODEOWNERS ├── CONTRIBUTING.md ├── ISSUE_TEMPLATE │ ├── bug-report.yml │ └── config.yml ├── dependabot.yml ├── labeler.yml ├── labeler_merged.yml ├── matchers │ └── pylint.json ├── pull_request_template.md └── workflows │ ├── ci.yml │ ├── configure.yml │ ├── format.yml │ ├── labeler.yml │ ├── pip.yml │ └── upstream.yml ├── .gitignore ├── .pre-commit-config.yaml ├── .readthedocs.yml ├── CMakeLists.txt ├── LICENSE ├── MANIFEST.in ├── README.rst ├── SECURITY.md ├── docs ├── Doxyfile ├── _static │ └── css │ │ └── custom.css ├── advanced │ ├── cast │ │ ├── chrono.rst │ │ ├── custom.rst │ │ ├── eigen.rst │ │ ├── functional.rst │ │ ├── index.rst │ │ ├── overview.rst │ │ ├── stl.rst │ │ └── strings.rst │ ├── classes.rst │ ├── embedding.rst │ ├── exceptions.rst │ ├── functions.rst │ ├── misc.rst │ ├── pycpp │ │ ├── index.rst │ │ ├── numpy.rst │ │ ├── object.rst │ │ └── utilities.rst │ └── smart_ptrs.rst ├── basics.rst ├── benchmark.py ├── benchmark.rst ├── changelog.rst ├── classes.rst ├── cmake │ └── index.rst ├── compiling.rst ├── conf.py ├── faq.rst ├── index.rst ├── installing.rst ├── limitations.rst ├── pybind11-logo.png ├── pybind11_vs_boost_python1.png ├── pybind11_vs_boost_python1.svg ├── pybind11_vs_boost_python2.png ├── pybind11_vs_boost_python2.svg ├── reference.rst ├── release.rst ├── requirements.txt └── upgrade.rst ├── include └── pybind11 │ ├── attr.h │ ├── buffer_info.h │ ├── cast.h │ ├── chrono.h │ ├── common.h │ ├── complex.h │ ├── detail │ ├── class.h │ ├── common.h │ ├── descr.h │ ├── init.h │ ├── internals.h │ ├── type_caster_base.h │ └── typeid.h │ ├── eigen.h │ ├── eigen │ ├── common.h │ ├── matrix.h │ └── tensor.h │ ├── embed.h │ ├── eval.h │ ├── functional.h │ ├── gil.h │ ├── gil_safe_call_once.h │ ├── iostream.h │ ├── numpy.h │ ├── operators.h │ ├── options.h │ ├── pybind11.h │ ├── pytypes.h │ ├── stl.h │ ├── stl │ └── filesystem.h │ ├── stl_bind.h │ ├── type_caster_pyobject_ptr.h │ └── typing.h ├── noxfile.py ├── pybind11 ├── __init__.py ├── __main__.py ├── _version.py ├── commands.py ├── py.typed └── setup_helpers.py ├── pyproject.toml ├── setup.cfg ├── setup.py ├── tests ├── CMakeLists.txt ├── conftest.py ├── constructor_stats.h ├── cross_module_gil_utils.cpp ├── cross_module_interleaved_error_already_set.cpp ├── eigen_tensor_avoid_stl_array.cpp ├── env.py ├── extra_python_package │ ├── pytest.ini │ └── test_files.py ├── extra_setuptools │ ├── pytest.ini │ └── test_setuphelper.py ├── local_bindings.h ├── object.h ├── pybind11_cross_module_tests.cpp ├── pybind11_tests.cpp ├── pybind11_tests.h ├── pytest.ini ├── requirements.txt ├── test_async.cpp ├── test_async.py ├── test_buffers.cpp ├── test_buffers.py ├── test_builtin_casters.cpp ├── test_builtin_casters.py ├── test_call_policies.cpp ├── test_call_policies.py ├── test_callbacks.cpp ├── test_callbacks.py ├── test_chrono.cpp ├── test_chrono.py ├── test_class.cpp ├── test_class.py ├── test_cmake_build │ ├── CMakeLists.txt │ ├── embed.cpp │ ├── installed_embed │ │ └── CMakeLists.txt │ ├── installed_function │ │ └── CMakeLists.txt │ ├── installed_target │ │ └── CMakeLists.txt │ ├── main.cpp │ ├── subdirectory_embed │ │ └── CMakeLists.txt │ ├── subdirectory_function │ │ └── CMakeLists.txt │ ├── subdirectory_target │ │ └── CMakeLists.txt │ └── test.py ├── test_const_name.cpp ├── test_const_name.py ├── test_constants_and_functions.cpp ├── test_constants_and_functions.py ├── test_copy_move.cpp ├── test_copy_move.py ├── test_custom_type_casters.cpp ├── test_custom_type_casters.py ├── test_custom_type_setup.cpp ├── test_custom_type_setup.py ├── test_docstring_options.cpp ├── test_docstring_options.py ├── test_eigen_matrix.cpp ├── test_eigen_matrix.py ├── test_eigen_tensor.cpp ├── test_eigen_tensor.inl ├── test_eigen_tensor.py ├── test_embed │ ├── CMakeLists.txt │ ├── catch.cpp │ ├── external_module.cpp │ ├── test_interpreter.cpp │ ├── test_interpreter.py │ └── test_trampoline.py ├── test_enum.cpp ├── test_enum.py ├── test_eval.cpp ├── test_eval.py ├── test_eval_call.py ├── test_exceptions.cpp ├── test_exceptions.h ├── test_exceptions.py ├── test_factory_constructors.cpp ├── test_factory_constructors.py ├── test_gil_scoped.cpp ├── test_gil_scoped.py ├── test_iostream.cpp ├── test_iostream.py ├── test_kwargs_and_defaults.cpp ├── test_kwargs_and_defaults.py ├── test_local_bindings.cpp ├── test_local_bindings.py ├── test_methods_and_attributes.cpp ├── test_methods_and_attributes.py ├── test_modules.cpp ├── test_modules.py ├── test_multiple_inheritance.cpp ├── test_multiple_inheritance.py ├── test_numpy_array.cpp ├── test_numpy_array.py ├── test_numpy_dtypes.cpp ├── test_numpy_dtypes.py ├── test_numpy_vectorize.cpp ├── test_numpy_vectorize.py ├── test_opaque_types.cpp ├── test_opaque_types.py ├── test_operator_overloading.cpp ├── test_operator_overloading.py ├── test_pickling.cpp ├── test_pickling.py ├── test_python_multiple_inheritance.cpp ├── test_python_multiple_inheritance.py ├── test_pytypes.cpp ├── test_pytypes.py ├── test_sequences_and_iterators.cpp ├── test_sequences_and_iterators.py ├── test_smart_ptr.cpp ├── test_smart_ptr.py ├── test_stl.cpp ├── test_stl.py ├── test_stl_binders.cpp ├── test_stl_binders.py ├── test_tagbased_polymorphic.cpp ├── test_tagbased_polymorphic.py ├── test_thread.cpp ├── test_thread.py ├── test_type_caster_pyobject_ptr.cpp ├── test_type_caster_pyobject_ptr.py ├── test_union.cpp ├── test_union.py ├── test_unnamed_namespace_a.cpp ├── test_unnamed_namespace_a.py ├── test_unnamed_namespace_b.cpp ├── test_unnamed_namespace_b.py ├── test_vector_unique_ptr_member.cpp ├── test_vector_unique_ptr_member.py ├── test_virtual_functions.cpp ├── test_virtual_functions.py ├── valgrind-numpy-scipy.supp └── valgrind-python.supp └── tools ├── FindCatch.cmake ├── FindEigen3.cmake ├── FindPythonLibsNew.cmake ├── JoinPaths.cmake ├── check-style.sh ├── cmake_uninstall.cmake.in ├── codespell_ignore_lines_from_errors.py ├── libsize.py ├── make_changelog.py ├── pybind11.pc.in ├── pybind11Common.cmake ├── pybind11Config.cmake.in ├── pybind11NewTools.cmake ├── pybind11Tools.cmake ├── pyproject.toml ├── setup_global.py.in └── setup_main.py.in /.gitignore: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/.gitignore -------------------------------------------------------------------------------- /.pre-commit-config.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/.pre-commit-config.yaml -------------------------------------------------------------------------------- /.pylintrc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/.pylintrc -------------------------------------------------------------------------------- /.readthedocs.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/.readthedocs.yaml -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/README.md -------------------------------------------------------------------------------- /data/camera_mount.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/data/camera_mount.STL -------------------------------------------------------------------------------- /data/demo_policy/stair_distill/config.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/data/demo_policy/stair_distill/config.yaml -------------------------------------------------------------------------------- /data/demo_policy/stair_distill/model_29.pt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/data/demo_policy/stair_distill/model_29.pt -------------------------------------------------------------------------------- /data/demo_policy/stair_rl/config.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/data/demo_policy/stair_rl/config.yaml -------------------------------------------------------------------------------- /data/demo_policy/stair_rl/model_8000.pt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/data/demo_policy/stair_rl/model_8000.pt -------------------------------------------------------------------------------- /data/go1/meshes/calf.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/data/go1/meshes/calf.dae -------------------------------------------------------------------------------- /data/go1/meshes/calf.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/data/go1/meshes/calf.stl -------------------------------------------------------------------------------- /data/go1/meshes/depthCamera.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/data/go1/meshes/depthCamera.dae -------------------------------------------------------------------------------- /data/go1/meshes/hip.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/data/go1/meshes/hip.dae -------------------------------------------------------------------------------- /data/go1/meshes/hip.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/data/go1/meshes/hip.stl -------------------------------------------------------------------------------- /data/go1/meshes/thigh.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/data/go1/meshes/thigh.dae -------------------------------------------------------------------------------- /data/go1/meshes/thigh.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/data/go1/meshes/thigh.stl -------------------------------------------------------------------------------- /data/go1/meshes/thigh_mirror.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/data/go1/meshes/thigh_mirror.dae -------------------------------------------------------------------------------- /data/go1/meshes/thigh_mirror.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/data/go1/meshes/thigh_mirror.stl -------------------------------------------------------------------------------- /data/go1/meshes/trunk.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/data/go1/meshes/trunk.stl -------------------------------------------------------------------------------- /data/go1/meshes/ultraSound.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/data/go1/meshes/ultraSound.dae -------------------------------------------------------------------------------- /data/go1/urdf/go1.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/data/go1/urdf/go1.urdf -------------------------------------------------------------------------------- /data/mac_mini_mount.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/data/mac_mini_mount.stl -------------------------------------------------------------------------------- /deploy_requirements.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/deploy_requirements.txt -------------------------------------------------------------------------------- /docs/Makefile: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/docs/Makefile -------------------------------------------------------------------------------- /docs/requirements.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/docs/requirements.txt -------------------------------------------------------------------------------- /docs/source/conf.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/docs/source/conf.py -------------------------------------------------------------------------------- /docs/source/images/block_diagram_simplified.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/docs/source/images/block_diagram_simplified.png -------------------------------------------------------------------------------- /docs/source/images/camera_mount.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/docs/source/images/camera_mount.png -------------------------------------------------------------------------------- /docs/source/images/dog_tracer.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/docs/source/images/dog_tracer.gif -------------------------------------------------------------------------------- /docs/source/images/hardware_setup.JPEG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/docs/source/images/hardware_setup.JPEG -------------------------------------------------------------------------------- /docs/source/images/jumping_cod.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/docs/source/images/jumping_cod.jpg -------------------------------------------------------------------------------- /docs/source/images/mac_mini_mount.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/docs/source/images/mac_mini_mount.png -------------------------------------------------------------------------------- /docs/source/images/motor_calibration.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/docs/source/images/motor_calibration.gif -------------------------------------------------------------------------------- /docs/source/images/teaser.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/docs/source/images/teaser.gif -------------------------------------------------------------------------------- /docs/source/images/teaser_stepstone.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/docs/source/images/teaser_stepstone.gif -------------------------------------------------------------------------------- /docs/source/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/docs/source/index.rst -------------------------------------------------------------------------------- /docs/source/real_robot_setup.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/docs/source/real_robot_setup.rst -------------------------------------------------------------------------------- /docs/source/simulation_setup.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/docs/source/simulation_setup.rst -------------------------------------------------------------------------------- /docs/source/training_a_new_policy.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/docs/source/training_a_new_policy.rst -------------------------------------------------------------------------------- /docs/source/utilities.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/docs/source/utilities.rst -------------------------------------------------------------------------------- /pytype.cfg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/pytype.cfg -------------------------------------------------------------------------------- /requirements.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/requirements.txt -------------------------------------------------------------------------------- /rsl_rl/.gitignore: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/.gitignore -------------------------------------------------------------------------------- /rsl_rl/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/LICENSE -------------------------------------------------------------------------------- /rsl_rl/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/README.md -------------------------------------------------------------------------------- /rsl_rl/licenses/dependencies/numpy_license.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/licenses/dependencies/numpy_license.txt -------------------------------------------------------------------------------- /rsl_rl/licenses/dependencies/torch_license.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/licenses/dependencies/torch_license.txt -------------------------------------------------------------------------------- /rsl_rl/rsl_rl/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/rsl_rl/__init__.py -------------------------------------------------------------------------------- /rsl_rl/rsl_rl/algorithms/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/rsl_rl/algorithms/__init__.py -------------------------------------------------------------------------------- /rsl_rl/rsl_rl/algorithms/ppo.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/rsl_rl/algorithms/ppo.py -------------------------------------------------------------------------------- /rsl_rl/rsl_rl/env/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/rsl_rl/env/__init__.py -------------------------------------------------------------------------------- /rsl_rl/rsl_rl/env/vec_env.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/rsl_rl/env/vec_env.py -------------------------------------------------------------------------------- /rsl_rl/rsl_rl/modules/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/rsl_rl/modules/__init__.py -------------------------------------------------------------------------------- /rsl_rl/rsl_rl/modules/actor_critic.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/rsl_rl/modules/actor_critic.py -------------------------------------------------------------------------------- /rsl_rl/rsl_rl/modules/actor_critic_recurrent.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/rsl_rl/modules/actor_critic_recurrent.py -------------------------------------------------------------------------------- /rsl_rl/rsl_rl/runners/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/rsl_rl/runners/__init__.py -------------------------------------------------------------------------------- /rsl_rl/rsl_rl/runners/on_policy_runner.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/rsl_rl/runners/on_policy_runner.py -------------------------------------------------------------------------------- /rsl_rl/rsl_rl/storage/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/rsl_rl/storage/__init__.py -------------------------------------------------------------------------------- /rsl_rl/rsl_rl/storage/rollout_storage.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/rsl_rl/storage/rollout_storage.py -------------------------------------------------------------------------------- /rsl_rl/rsl_rl/utils/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/rsl_rl/utils/__init__.py -------------------------------------------------------------------------------- /rsl_rl/rsl_rl/utils/utils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/rsl_rl/utils/utils.py -------------------------------------------------------------------------------- /rsl_rl/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/rsl_rl/setup.py -------------------------------------------------------------------------------- /src/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/agents/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/agents/heightmap_prediction/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/agents/heightmap_prediction/configs/lstm_heightmap.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/agents/heightmap_prediction/configs/lstm_heightmap.py -------------------------------------------------------------------------------- /src/agents/heightmap_prediction/eval.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/agents/heightmap_prediction/eval.py -------------------------------------------------------------------------------- /src/agents/heightmap_prediction/eval_real.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/agents/heightmap_prediction/eval_real.py -------------------------------------------------------------------------------- /src/agents/heightmap_prediction/lstm_heightmap_predictor.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/agents/heightmap_prediction/lstm_heightmap_predictor.py -------------------------------------------------------------------------------- /src/agents/heightmap_prediction/replay_buffer.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/agents/heightmap_prediction/replay_buffer.py -------------------------------------------------------------------------------- /src/agents/heightmap_prediction/train_dagger.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/agents/heightmap_prediction/train_dagger.py -------------------------------------------------------------------------------- /src/agents/ppo/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/agents/ppo/configs/bound_on_platform.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/agents/ppo/configs/bound_on_platform.py -------------------------------------------------------------------------------- /src/agents/ppo/configs/bound_on_stair.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/agents/ppo/configs/bound_on_stair.py -------------------------------------------------------------------------------- /src/agents/ppo/configs/bound_together.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/agents/ppo/configs/bound_together.py -------------------------------------------------------------------------------- /src/agents/ppo/configs/bound_together_e2e.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/agents/ppo/configs/bound_together_e2e.py -------------------------------------------------------------------------------- /src/agents/ppo/configs/bound_together_noswingref.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/agents/ppo/configs/bound_together_noswingref.py -------------------------------------------------------------------------------- /src/agents/ppo/configs/bound_together_speed.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/agents/ppo/configs/bound_together_speed.py -------------------------------------------------------------------------------- /src/agents/ppo/configs/go1_single_jump_bound.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/agents/ppo/configs/go1_single_jump_bound.py -------------------------------------------------------------------------------- /src/agents/ppo/configs/go1_single_jump_pronk.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/agents/ppo/configs/go1_single_jump_pronk.py -------------------------------------------------------------------------------- /src/agents/ppo/configs/trot_together.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/agents/ppo/configs/trot_together.py -------------------------------------------------------------------------------- /src/agents/ppo/configs/trot_together_speed.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/agents/ppo/configs/trot_together_speed.py -------------------------------------------------------------------------------- /src/agents/ppo/eval.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/agents/ppo/eval.py -------------------------------------------------------------------------------- /src/agents/ppo/replay_actions.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/agents/ppo/replay_actions.py -------------------------------------------------------------------------------- /src/agents/ppo/train.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/agents/ppo/train.py -------------------------------------------------------------------------------- /src/configs/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/configs/defaults/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/configs/defaults/asset_options.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/configs/defaults/asset_options.py -------------------------------------------------------------------------------- /src/configs/defaults/go1_camera_config.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/configs/defaults/go1_camera_config.py -------------------------------------------------------------------------------- /src/configs/defaults/sim_config.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/configs/defaults/sim_config.py -------------------------------------------------------------------------------- /src/configs/perception.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/configs/perception.launch -------------------------------------------------------------------------------- /src/configs/supervisord.conf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/configs/supervisord.conf -------------------------------------------------------------------------------- /src/controllers/centroidal_body_controller_example.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/controllers/centroidal_body_controller_example.py -------------------------------------------------------------------------------- /src/controllers/centroidal_body_controller_stand_example.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/controllers/centroidal_body_controller_stand_example.py -------------------------------------------------------------------------------- /src/controllers/phase_gait_generator.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/controllers/phase_gait_generator.py -------------------------------------------------------------------------------- /src/controllers/phase_gait_generator_example.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/controllers/phase_gait_generator_example.py -------------------------------------------------------------------------------- /src/controllers/qp_torque_optimizer.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/controllers/qp_torque_optimizer.py -------------------------------------------------------------------------------- /src/controllers/qp_torque_optimizer_numpy.py.bak: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/controllers/qp_torque_optimizer_numpy.py.bak -------------------------------------------------------------------------------- /src/controllers/raibert_swing_leg_controller.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/controllers/raibert_swing_leg_controller.py -------------------------------------------------------------------------------- /src/envs/configs/bound_together.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/envs/configs/bound_together.py -------------------------------------------------------------------------------- /src/envs/env_wrappers.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/envs/env_wrappers.py -------------------------------------------------------------------------------- /src/envs/go1_rewards.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/envs/go1_rewards.py -------------------------------------------------------------------------------- /src/envs/jump_env.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/envs/jump_env.py -------------------------------------------------------------------------------- /src/envs/terrain.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/envs/terrain.py -------------------------------------------------------------------------------- /src/robots/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/robots/gamepad_reader.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/robots/gamepad_reader.py -------------------------------------------------------------------------------- /src/robots/go1.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/robots/go1.py -------------------------------------------------------------------------------- /src/robots/go1_robot.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/robots/go1_robot.py -------------------------------------------------------------------------------- /src/robots/go1_robot_exercise_example.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/robots/go1_robot_exercise_example.py -------------------------------------------------------------------------------- /src/robots/motors.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/robots/motors.py -------------------------------------------------------------------------------- /src/robots/realsense_image_capture.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/robots/realsense_image_capture.py -------------------------------------------------------------------------------- /src/robots/robot.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/robots/robot.py -------------------------------------------------------------------------------- /src/robots/robot_state_estimator.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/robots/robot_state_estimator.py -------------------------------------------------------------------------------- /src/utils/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/utils/dog_tracer/assets/app.css: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/utils/dog_tracer/assets/app.css -------------------------------------------------------------------------------- /src/utils/dog_tracer/dog_tracer.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/utils/dog_tracer/dog_tracer.py -------------------------------------------------------------------------------- /src/utils/dog_tracer/video_generator_example.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/utils/dog_tracer/video_generator_example.py -------------------------------------------------------------------------------- /src/utils/go1_camera_calibration.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/utils/go1_camera_calibration.py -------------------------------------------------------------------------------- /src/utils/go1_camera_calibration_sim.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/utils/go1_camera_calibration_sim.py -------------------------------------------------------------------------------- /src/utils/go1_motor_calibration.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/utils/go1_motor_calibration.py -------------------------------------------------------------------------------- /src/utils/moving_window_filter.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/utils/moving_window_filter.py -------------------------------------------------------------------------------- /src/utils/pilots_eye/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/utils/pilots_eye/assets/img/placeholder.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/utils/pilots_eye/assets/img/placeholder.png -------------------------------------------------------------------------------- /src/utils/pilots_eye/index.html: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/utils/pilots_eye/index.html -------------------------------------------------------------------------------- /src/utils/pilots_eye/pilots_eye.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/utils/pilots_eye/pilots_eye.py -------------------------------------------------------------------------------- /src/utils/pilots_eye/scripts/eventemitter2.min.js: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/utils/pilots_eye/scripts/eventemitter2.min.js -------------------------------------------------------------------------------- /src/utils/pilots_eye/scripts/roslib.min.js: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/utils/pilots_eye/scripts/roslib.min.js -------------------------------------------------------------------------------- /src/utils/torch_utils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/src/utils/torch_utils.py -------------------------------------------------------------------------------- /third_party/eigen3/.DS_Store: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/.DS_Store -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/Cholesky: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/Cholesky -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/CholmodSupport: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/CholmodSupport -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/Core: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/Core -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/Dense: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/Dense -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/Eigen: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/Eigen -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/Eigenvalues: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/Eigenvalues -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/Geometry: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/Geometry -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/Householder: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/Householder -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/IterativeLinearSolvers: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/IterativeLinearSolvers -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/Jacobi: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/Jacobi -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/KLUSupport: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/KLUSupport -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/LU: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/LU -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/MetisSupport: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/MetisSupport -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/OrderingMethods: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/OrderingMethods -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/PaStiXSupport: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/PaStiXSupport -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/PardisoSupport: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/PardisoSupport -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/QR: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/QR -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/QtAlignedMalloc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/QtAlignedMalloc -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/SPQRSupport: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/SPQRSupport -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/SVD: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/SVD -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/Sparse: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/Sparse -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/SparseCholesky: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/SparseCholesky -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/SparseCore: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/SparseCore -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/SparseLU: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/SparseLU -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/SparseQR: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/SparseQR -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/StdDeque: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/StdDeque -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/StdList: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/StdList -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/StdVector: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/StdVector -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/SuperLUSupport: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/SuperLUSupport -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/UmfPackSupport: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/UmfPackSupport -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Cholesky/LDLT.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Cholesky/LDLT.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Cholesky/LLT.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Cholesky/LLT.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Cholesky/LLT_LAPACKE.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Cholesky/LLT_LAPACKE.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/CholmodSupport/CholmodSupport.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/CholmodSupport/CholmodSupport.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/ArithmeticSequence.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/ArithmeticSequence.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Array.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Array.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/ArrayBase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/ArrayBase.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/ArrayWrapper.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/ArrayWrapper.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Assign.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Assign.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/AssignEvaluator.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/AssignEvaluator.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Assign_MKL.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Assign_MKL.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/BandMatrix.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/BandMatrix.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Block.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Block.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/BooleanRedux.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/BooleanRedux.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/CommaInitializer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/CommaInitializer.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/ConditionEstimator.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/ConditionEstimator.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/CoreEvaluators.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/CoreEvaluators.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/CoreIterators.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/CoreIterators.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/CwiseBinaryOp.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/CwiseBinaryOp.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/CwiseNullaryOp.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/CwiseNullaryOp.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/CwiseTernaryOp.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/CwiseTernaryOp.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/CwiseUnaryOp.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/CwiseUnaryOp.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/CwiseUnaryView.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/CwiseUnaryView.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/DenseBase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/DenseBase.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/DenseCoeffsBase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/DenseCoeffsBase.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/DenseStorage.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/DenseStorage.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Diagonal.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Diagonal.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/DiagonalMatrix.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/DiagonalMatrix.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/DiagonalProduct.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/DiagonalProduct.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Dot.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Dot.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/EigenBase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/EigenBase.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/ForceAlignedAccess.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/ForceAlignedAccess.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Fuzzy.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Fuzzy.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/GeneralProduct.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/GeneralProduct.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/GenericPacketMath.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/GenericPacketMath.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/GlobalFunctions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/GlobalFunctions.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/IO.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/IO.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/IndexedView.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/IndexedView.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Inverse.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Inverse.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Map.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Map.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/MapBase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/MapBase.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/MathFunctions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/MathFunctions.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/MathFunctionsImpl.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/MathFunctionsImpl.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Matrix.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Matrix.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/MatrixBase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/MatrixBase.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/NestByValue.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/NestByValue.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/NoAlias.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/NoAlias.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/NumTraits.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/NumTraits.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/PartialReduxEvaluator.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/PartialReduxEvaluator.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/PermutationMatrix.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/PermutationMatrix.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/PlainObjectBase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/PlainObjectBase.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Product.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Product.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/ProductEvaluators.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/ProductEvaluators.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Random.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Random.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Redux.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Redux.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Ref.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Ref.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Replicate.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Replicate.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Reshaped.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Reshaped.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/ReturnByValue.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/ReturnByValue.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Reverse.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Reverse.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Select.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Select.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/SelfAdjointView.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/SelfAdjointView.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/SelfCwiseBinaryOp.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/SelfCwiseBinaryOp.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Solve.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Solve.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/SolveTriangular.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/SolveTriangular.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/SolverBase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/SolverBase.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/StableNorm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/StableNorm.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/StlIterators.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/StlIterators.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Stride.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Stride.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Swap.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Swap.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Transpose.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Transpose.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Transpositions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Transpositions.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/TriangularMatrix.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/TriangularMatrix.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/VectorBlock.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/VectorBlock.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/VectorwiseOp.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/VectorwiseOp.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/Visitor.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/Visitor.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/AVX/Complex.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/AVX/Complex.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/AVX/MathFunctions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/AVX/MathFunctions.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/AVX/PacketMath.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/AVX/PacketMath.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/AVX/TypeCasting.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/AVX/TypeCasting.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/AVX512/Complex.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/AVX512/Complex.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/AVX512/MathFunctions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/AVX512/MathFunctions.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/AVX512/PacketMath.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/AVX512/PacketMath.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/AVX512/TypeCasting.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/AVX512/TypeCasting.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/AltiVec/Complex.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/AltiVec/Complex.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/AltiVec/PacketMath.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/AltiVec/PacketMath.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/CUDA/Complex.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/CUDA/Complex.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/Default/BFloat16.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/Default/BFloat16.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/Default/ConjHelper.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/Default/ConjHelper.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/Default/Half.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/Default/Half.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/Default/Settings.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/Default/Settings.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/Default/TypeCasting.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/Default/TypeCasting.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/GPU/MathFunctions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/GPU/MathFunctions.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/GPU/PacketMath.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/GPU/PacketMath.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/GPU/TypeCasting.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/GPU/TypeCasting.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/MSA/Complex.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/MSA/Complex.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/MSA/MathFunctions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/MSA/MathFunctions.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/MSA/PacketMath.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/MSA/PacketMath.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/NEON/Complex.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/NEON/Complex.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/NEON/MathFunctions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/NEON/MathFunctions.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/NEON/PacketMath.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/NEON/PacketMath.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/NEON/TypeCasting.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/NEON/TypeCasting.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/SSE/Complex.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/SSE/Complex.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/SSE/MathFunctions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/SSE/MathFunctions.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/SSE/PacketMath.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/SSE/PacketMath.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/SSE/TypeCasting.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/SSE/TypeCasting.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/SYCL/InteropHeaders.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/SYCL/InteropHeaders.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/SYCL/MathFunctions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/SYCL/MathFunctions.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/SYCL/PacketMath.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/SYCL/PacketMath.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/SYCL/SyclMemoryModel.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/SYCL/SyclMemoryModel.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/SYCL/TypeCasting.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/SYCL/TypeCasting.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/ZVector/Complex.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/ZVector/Complex.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/arch/ZVector/PacketMath.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/arch/ZVector/PacketMath.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/functors/BinaryFunctors.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/functors/BinaryFunctors.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/functors/NullaryFunctors.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/functors/NullaryFunctors.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/functors/StlFunctors.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/functors/StlFunctors.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/functors/TernaryFunctors.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/functors/TernaryFunctors.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/functors/UnaryFunctors.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/functors/UnaryFunctors.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/products/Parallelizer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/products/Parallelizer.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/util/BlasUtil.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/util/BlasUtil.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/util/Constants.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/util/Constants.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/util/ForwardDeclarations.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/util/ForwardDeclarations.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/util/IndexedViewHelper.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/util/IndexedViewHelper.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/util/IntegralConstant.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/util/IntegralConstant.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/util/MKL_support.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/util/MKL_support.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/util/Macros.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/util/Macros.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/util/Memory.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/util/Memory.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/util/Meta.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/util/Meta.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/util/NonMPL2.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/util/NonMPL2.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/util/ReshapedHelper.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/util/ReshapedHelper.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/util/StaticAssert.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/util/StaticAssert.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/util/SymbolicIndex.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/util/SymbolicIndex.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Core/util/XprHelper.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Core/util/XprHelper.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Eigenvalues/ComplexEigenSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Eigenvalues/ComplexEigenSolver.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Eigenvalues/ComplexSchur.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Eigenvalues/ComplexSchur.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Eigenvalues/EigenSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Eigenvalues/EigenSolver.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Eigenvalues/RealQZ.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Eigenvalues/RealQZ.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Eigenvalues/RealSchur.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Eigenvalues/RealSchur.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Geometry/AlignedBox.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Geometry/AlignedBox.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Geometry/AngleAxis.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Geometry/AngleAxis.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Geometry/EulerAngles.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Geometry/EulerAngles.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Geometry/Homogeneous.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Geometry/Homogeneous.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Geometry/Hyperplane.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Geometry/Hyperplane.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Geometry/OrthoMethods.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Geometry/OrthoMethods.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Geometry/ParametrizedLine.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Geometry/ParametrizedLine.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Geometry/Quaternion.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Geometry/Quaternion.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Geometry/Rotation2D.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Geometry/Rotation2D.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Geometry/RotationBase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Geometry/RotationBase.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Geometry/Scaling.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Geometry/Scaling.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Geometry/Transform.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Geometry/Transform.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Geometry/Translation.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Geometry/Translation.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Geometry/Umeyama.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Geometry/Umeyama.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Geometry/arch/Geometry_SSE.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Geometry/arch/Geometry_SSE.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Householder/BlockHouseholder.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Householder/BlockHouseholder.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Householder/Householder.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Householder/Householder.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/Jacobi/Jacobi.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/Jacobi/Jacobi.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/KLUSupport/KLUSupport.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/KLUSupport/KLUSupport.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/LU/Determinant.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/LU/Determinant.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/LU/FullPivLU.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/LU/FullPivLU.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/LU/InverseImpl.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/LU/InverseImpl.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/LU/PartialPivLU.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/LU/PartialPivLU.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/LU/PartialPivLU_LAPACKE.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/LU/PartialPivLU_LAPACKE.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/LU/arch/Inverse_SSE.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/LU/arch/Inverse_SSE.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/MetisSupport/MetisSupport.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/MetisSupport/MetisSupport.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/OrderingMethods/Amd.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/OrderingMethods/Amd.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/OrderingMethods/Eigen_Colamd.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/OrderingMethods/Eigen_Colamd.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/OrderingMethods/Ordering.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/OrderingMethods/Ordering.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/PaStiXSupport/PaStiXSupport.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/PaStiXSupport/PaStiXSupport.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/QR/ColPivHouseholderQR.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/QR/ColPivHouseholderQR.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/QR/FullPivHouseholderQR.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/QR/FullPivHouseholderQR.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/QR/HouseholderQR.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/QR/HouseholderQR.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/QR/HouseholderQR_LAPACKE.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/QR/HouseholderQR_LAPACKE.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SVD/BDCSVD.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SVD/BDCSVD.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SVD/JacobiSVD.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SVD/JacobiSVD.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SVD/JacobiSVD_LAPACKE.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SVD/JacobiSVD_LAPACKE.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SVD/SVDBase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SVD/SVDBase.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SVD/UpperBidiagonalization.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SVD/UpperBidiagonalization.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/AmbiVector.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/AmbiVector.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/CompressedStorage.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/CompressedStorage.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/SparseAssign.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/SparseAssign.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/SparseBlock.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/SparseBlock.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/SparseColEtree.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/SparseColEtree.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/SparseDot.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/SparseDot.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/SparseFuzzy.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/SparseFuzzy.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/SparseMap.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/SparseMap.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/SparseMatrix.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/SparseMatrix.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/SparseMatrixBase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/SparseMatrixBase.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/SparsePermutation.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/SparsePermutation.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/SparseProduct.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/SparseProduct.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/SparseRedux.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/SparseRedux.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/SparseRef.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/SparseRef.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/SparseSolverBase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/SparseSolverBase.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/SparseTranspose.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/SparseTranspose.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/SparseUtil.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/SparseUtil.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/SparseVector.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/SparseVector.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/SparseView.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/SparseView.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseCore/TriangularSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseCore/TriangularSolver.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseLU/SparseLU.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseLU/SparseLU.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseLU/SparseLUImpl.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseLU/SparseLUImpl.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseLU/SparseLU_Memory.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseLU/SparseLU_Memory.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseLU/SparseLU_Structs.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseLU/SparseLU_Structs.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseLU/SparseLU_Utils.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseLU/SparseLU_Utils.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseLU/SparseLU_column_dfs.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseLU/SparseLU_column_dfs.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseLU/SparseLU_panel_bmod.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseLU/SparseLU_panel_bmod.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseLU/SparseLU_panel_dfs.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseLU/SparseLU_panel_dfs.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseLU/SparseLU_pivotL.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseLU/SparseLU_pivotL.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseLU/SparseLU_pruneL.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseLU/SparseLU_pruneL.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/SparseQR/SparseQR.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/SparseQR/SparseQR.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/StlSupport/StdDeque.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/StlSupport/StdDeque.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/StlSupport/StdList.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/StlSupport/StdList.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/StlSupport/StdVector.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/StlSupport/StdVector.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/StlSupport/details.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/StlSupport/details.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/misc/Image.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/misc/Image.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/misc/Kernel.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/misc/Kernel.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/misc/RealSvd2x2.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/misc/RealSvd2x2.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/misc/blas.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/misc/blas.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/misc/lapack.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/misc/lapack.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/misc/lapacke.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/misc/lapacke.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/misc/lapacke_mangling.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/misc/lapacke_mangling.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/plugins/ArrayCwiseBinaryOps.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/plugins/ArrayCwiseBinaryOps.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/plugins/ArrayCwiseUnaryOps.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/plugins/ArrayCwiseUnaryOps.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/plugins/BlockMethods.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/plugins/BlockMethods.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/plugins/CommonCwiseBinaryOps.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/plugins/CommonCwiseBinaryOps.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/plugins/CommonCwiseUnaryOps.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/plugins/CommonCwiseUnaryOps.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/plugins/IndexedViewMethods.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/plugins/IndexedViewMethods.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/plugins/MatrixCwiseBinaryOps.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/plugins/MatrixCwiseBinaryOps.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/plugins/MatrixCwiseUnaryOps.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/plugins/MatrixCwiseUnaryOps.h -------------------------------------------------------------------------------- /third_party/eigen3/include/Eigen/src/plugins/ReshapedMethods.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/Eigen/src/plugins/ReshapedMethods.h -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/CMakeLists.txt -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/AdolcForward: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/AdolcForward -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/AlignedVector3: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/AlignedVector3 -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/ArpackSupport: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/ArpackSupport -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/AutoDiff: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/AutoDiff -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/BVH: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/BVH -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/CMakeLists.txt -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/CXX11/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/CXX11/CMakeLists.txt -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/CXX11/Tensor: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/CXX11/Tensor -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/CXX11/TensorSymmetry: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/CXX11/TensorSymmetry -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/CXX11/ThreadPool: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/CXX11/ThreadPool -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/EulerAngles: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/EulerAngles -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/FFT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/FFT -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/IterativeSolvers: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/IterativeSolvers -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/KroneckerProduct: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/KroneckerProduct -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/LevenbergMarquardt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/LevenbergMarquardt -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/MPRealSupport: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/MPRealSupport -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/MatrixFunctions: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/MatrixFunctions -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/MoreVectorization: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/MoreVectorization -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/NonLinearOptimization: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/NonLinearOptimization -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/NumericalDiff: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/NumericalDiff -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/OpenGLSupport: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/OpenGLSupport -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/Polynomials: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/Polynomials -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/Skyline: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/Skyline -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/SparseExtra: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/SparseExtra -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/SpecialFunctions: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/SpecialFunctions -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/Splines: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/Splines -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/src/BVH/BVAlgorithms.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/src/BVH/BVAlgorithms.h -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/src/BVH/KdBVH.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/src/BVH/KdBVH.h -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/src/FFT/ei_fftw_impl.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/src/FFT/ei_fftw_impl.h -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/Eigen/src/Splines/Spline.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/Eigen/src/Splines/Spline.h -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/README.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/README.txt -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/bench/bench_svd.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/bench/bench_svd.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/doc/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/doc/CMakeLists.txt -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/doc/Overview.dox: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/doc/Overview.dox -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/doc/SYCL.dox: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/doc/SYCL.dox -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/doc/eigendoxy_layout.xml.in: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/doc/eigendoxy_layout.xml.in -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/doc/examples/BVH_Example.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/doc/examples/BVH_Example.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/doc/examples/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/doc/examples/CMakeLists.txt -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/doc/examples/EulerAngles.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/doc/examples/EulerAngles.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/doc/examples/FFT.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/doc/examples/FFT.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/doc/examples/MatrixPower.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/doc/examples/MatrixPower.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/doc/examples/MatrixSine.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/doc/examples/MatrixSine.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/doc/examples/MatrixSinh.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/doc/examples/MatrixSinh.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/doc/snippets/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/doc/snippets/CMakeLists.txt -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/BVH.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/BVH.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/CMakeLists.txt -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/EulerAngles.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/EulerAngles.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/FFT.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/FFT.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/FFTW.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/FFTW.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/NumericalDiff.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/NumericalDiff.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/alignedvector3.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/alignedvector3.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/autodiff.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/autodiff.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/autodiff_scalar.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/autodiff_scalar.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/bessel_functions.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/bessel_functions.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_eventcount.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_eventcount.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_maxsizevector.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_maxsizevector.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_meta.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_meta.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_runqueue.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_runqueue.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_argmax.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_argmax.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_assign.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_assign.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_casts.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_casts.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_const.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_const.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_device.cu: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_device.cu -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_empty.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_empty.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_expr.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_expr.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_fft.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_fft.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_gpu.cu: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_gpu.cu -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_ifft.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_ifft.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_intdiv.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_intdiv.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_io.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_io.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_lvalue.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_lvalue.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_map.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_map.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_math.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_math.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_move.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_move.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_patch.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_patch.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_random.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_random.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_ref.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_ref.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_scan.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_scan.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_simple.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_simple.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_sugar.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_sugar.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_sycl.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_sycl.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/cxx11_tensor_trace.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/cxx11_tensor_trace.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/dgmres.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/dgmres.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/forward_adolc.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/forward_adolc.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/gmres.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/gmres.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/kronecker_product.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/kronecker_product.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/levenberg_marquardt.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/levenberg_marquardt.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/matrix_exponential.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/matrix_exponential.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/matrix_function.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/matrix_function.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/matrix_functions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/matrix_functions.h -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/matrix_power.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/matrix_power.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/matrix_square_root.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/matrix_square_root.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/minres.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/minres.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/mpreal/mpreal.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/mpreal/mpreal.h -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/mpreal_support.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/mpreal_support.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/openglsupport.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/openglsupport.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/polynomialsolver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/polynomialsolver.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/polynomialutils.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/polynomialutils.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/sparse_extra.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/sparse_extra.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/special_functions.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/special_functions.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/special_packetmath.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/special_packetmath.cpp -------------------------------------------------------------------------------- /third_party/eigen3/include/unsupported/test/splines.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/eigen3/include/unsupported/test/splines.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/.gitignore: -------------------------------------------------------------------------------- 1 | build 2 | 3 | *.o 4 | .vscode 5 | -------------------------------------------------------------------------------- /third_party/go1_sdk/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/CMakeLists.txt -------------------------------------------------------------------------------- /third_party/go1_sdk/CMakeLists_bak.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/CMakeLists_bak.txt -------------------------------------------------------------------------------- /third_party/go1_sdk/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/LICENSE -------------------------------------------------------------------------------- /third_party/go1_sdk/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/README.md -------------------------------------------------------------------------------- /third_party/go1_sdk/go1_python_interface.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/go1_python_interface.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/include/unitree_legged_sdk/a1_const.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/include/unitree_legged_sdk/a1_const.h -------------------------------------------------------------------------------- /third_party/go1_sdk/include/unitree_legged_sdk/aliengo_const.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/include/unitree_legged_sdk/aliengo_const.h -------------------------------------------------------------------------------- /third_party/go1_sdk/include/unitree_legged_sdk/comm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/include/unitree_legged_sdk/comm.h -------------------------------------------------------------------------------- /third_party/go1_sdk/include/unitree_legged_sdk/go1_const.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/include/unitree_legged_sdk/go1_const.h -------------------------------------------------------------------------------- /third_party/go1_sdk/include/unitree_legged_sdk/joystick.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/include/unitree_legged_sdk/joystick.h -------------------------------------------------------------------------------- /third_party/go1_sdk/include/unitree_legged_sdk/loop.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/include/unitree_legged_sdk/loop.h -------------------------------------------------------------------------------- /third_party/go1_sdk/include/unitree_legged_sdk/quadruped.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/include/unitree_legged_sdk/quadruped.h -------------------------------------------------------------------------------- /third_party/go1_sdk/include/unitree_legged_sdk/safety.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/include/unitree_legged_sdk/safety.h -------------------------------------------------------------------------------- /third_party/go1_sdk/include/unitree_legged_sdk/udp.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/include/unitree_legged_sdk/udp.h -------------------------------------------------------------------------------- /third_party/go1_sdk/include/unitree_legged_sdk/unitree_legged_sdk.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/include/unitree_legged_sdk/unitree_legged_sdk.h -------------------------------------------------------------------------------- /third_party/go1_sdk/lib/cpp/amd64/libunitree_legged_sdk.a: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/lib/cpp/amd64/libunitree_legged_sdk.a -------------------------------------------------------------------------------- /third_party/go1_sdk/lib/cpp/arm64/libunitree_legged_sdk.a: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/lib/cpp/arm64/libunitree_legged_sdk.a -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.appveyor.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.appveyor.yml -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.clang-format: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.clang-format -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.clang-tidy: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.clang-tidy -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.cmake-format.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.cmake-format.yaml -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.codespell-ignore-lines: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.codespell-ignore-lines -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.gitattributes: -------------------------------------------------------------------------------- 1 | docs/*.svg binary 2 | -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.github/CODEOWNERS: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.github/CODEOWNERS -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.github/CONTRIBUTING.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.github/CONTRIBUTING.md -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.github/ISSUE_TEMPLATE/bug-report.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.github/ISSUE_TEMPLATE/bug-report.yml -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.github/ISSUE_TEMPLATE/config.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.github/ISSUE_TEMPLATE/config.yml -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.github/dependabot.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.github/dependabot.yml -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.github/labeler.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.github/labeler.yml -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.github/labeler_merged.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.github/labeler_merged.yml -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.github/matchers/pylint.json: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.github/matchers/pylint.json -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.github/pull_request_template.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.github/pull_request_template.md -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.github/workflows/ci.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.github/workflows/ci.yml -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.github/workflows/configure.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.github/workflows/configure.yml -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.github/workflows/format.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.github/workflows/format.yml -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.github/workflows/labeler.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.github/workflows/labeler.yml -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.github/workflows/pip.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.github/workflows/pip.yml -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.github/workflows/upstream.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.github/workflows/upstream.yml -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.gitignore: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.gitignore -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.pre-commit-config.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.pre-commit-config.yaml -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/.readthedocs.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/.readthedocs.yml -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/CMakeLists.txt -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/LICENSE -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/MANIFEST.in: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/MANIFEST.in -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/README.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/README.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/SECURITY.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/SECURITY.md -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/Doxyfile: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/Doxyfile -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/_static/css/custom.css: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/_static/css/custom.css -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/advanced/cast/chrono.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/advanced/cast/chrono.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/advanced/cast/custom.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/advanced/cast/custom.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/advanced/cast/eigen.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/advanced/cast/eigen.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/advanced/cast/functional.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/advanced/cast/functional.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/advanced/cast/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/advanced/cast/index.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/advanced/cast/overview.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/advanced/cast/overview.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/advanced/cast/stl.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/advanced/cast/stl.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/advanced/cast/strings.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/advanced/cast/strings.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/advanced/classes.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/advanced/classes.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/advanced/embedding.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/advanced/embedding.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/advanced/exceptions.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/advanced/exceptions.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/advanced/functions.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/advanced/functions.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/advanced/misc.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/advanced/misc.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/advanced/pycpp/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/advanced/pycpp/index.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/advanced/pycpp/numpy.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/advanced/pycpp/numpy.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/advanced/pycpp/object.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/advanced/pycpp/object.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/advanced/pycpp/utilities.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/advanced/pycpp/utilities.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/advanced/smart_ptrs.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/advanced/smart_ptrs.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/basics.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/basics.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/benchmark.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/benchmark.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/benchmark.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/benchmark.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/changelog.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/changelog.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/classes.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/classes.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/cmake/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/cmake/index.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/compiling.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/compiling.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/conf.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/conf.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/faq.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/faq.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/index.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/installing.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/installing.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/limitations.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/limitations.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/pybind11-logo.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/pybind11-logo.png -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/pybind11_vs_boost_python1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/pybind11_vs_boost_python1.png -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/pybind11_vs_boost_python1.svg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/pybind11_vs_boost_python1.svg -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/pybind11_vs_boost_python2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/pybind11_vs_boost_python2.png -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/pybind11_vs_boost_python2.svg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/pybind11_vs_boost_python2.svg -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/reference.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/reference.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/release.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/release.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/requirements.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/requirements.txt -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/docs/upgrade.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/docs/upgrade.rst -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/attr.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/attr.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/buffer_info.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/buffer_info.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/cast.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/cast.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/chrono.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/chrono.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/common.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/common.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/complex.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/complex.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/detail/class.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/detail/class.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/detail/common.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/detail/common.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/detail/descr.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/detail/descr.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/detail/init.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/detail/init.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/detail/internals.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/detail/internals.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/detail/typeid.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/detail/typeid.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/eigen.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/eigen.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/eigen/common.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/eigen/common.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/eigen/matrix.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/eigen/matrix.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/eigen/tensor.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/eigen/tensor.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/embed.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/embed.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/eval.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/eval.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/functional.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/functional.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/gil.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/gil.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/gil_safe_call_once.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/gil_safe_call_once.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/iostream.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/iostream.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/numpy.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/numpy.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/operators.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/operators.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/options.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/options.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/pybind11.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/pybind11.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/pytypes.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/pytypes.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/stl.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/stl.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/stl/filesystem.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/stl/filesystem.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/stl_bind.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/stl_bind.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/include/pybind11/typing.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/include/pybind11/typing.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/noxfile.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/noxfile.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/pybind11/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/pybind11/__init__.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/pybind11/__main__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/pybind11/__main__.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/pybind11/_version.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/pybind11/_version.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/pybind11/commands.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/pybind11/commands.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/pybind11/py.typed: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/pybind11/setup_helpers.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/pybind11/setup_helpers.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/pyproject.toml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/pyproject.toml -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/setup.cfg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/setup.cfg -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/setup.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/CMakeLists.txt -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/conftest.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/conftest.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/constructor_stats.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/constructor_stats.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/cross_module_gil_utils.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/cross_module_gil_utils.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/eigen_tensor_avoid_stl_array.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/eigen_tensor_avoid_stl_array.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/env.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/env.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/extra_python_package/pytest.ini: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/extra_setuptools/pytest.ini: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/local_bindings.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/local_bindings.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/object.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/object.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/pybind11_cross_module_tests.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/pybind11_cross_module_tests.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/pybind11_tests.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/pybind11_tests.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/pybind11_tests.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/pybind11_tests.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/pytest.ini: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/pytest.ini -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/requirements.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/requirements.txt -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_async.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_async.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_async.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_async.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_buffers.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_buffers.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_buffers.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_buffers.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_builtin_casters.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_builtin_casters.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_builtin_casters.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_builtin_casters.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_call_policies.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_call_policies.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_call_policies.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_call_policies.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_callbacks.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_callbacks.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_callbacks.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_callbacks.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_chrono.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_chrono.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_chrono.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_chrono.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_class.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_class.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_class.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_class.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_cmake_build/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_cmake_build/CMakeLists.txt -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_cmake_build/embed.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_cmake_build/embed.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_cmake_build/main.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_cmake_build/main.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_cmake_build/test.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_cmake_build/test.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_const_name.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_const_name.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_const_name.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_const_name.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_constants_and_functions.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_constants_and_functions.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_constants_and_functions.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_constants_and_functions.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_copy_move.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_copy_move.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_copy_move.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_copy_move.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_custom_type_casters.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_custom_type_casters.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_custom_type_casters.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_custom_type_casters.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_custom_type_setup.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_custom_type_setup.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_custom_type_setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_custom_type_setup.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_docstring_options.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_docstring_options.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_docstring_options.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_docstring_options.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_eigen_matrix.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_eigen_matrix.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_eigen_matrix.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_eigen_matrix.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_eigen_tensor.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_eigen_tensor.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_eigen_tensor.inl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_eigen_tensor.inl -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_eigen_tensor.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_eigen_tensor.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_embed/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_embed/CMakeLists.txt -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_embed/catch.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_embed/catch.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_embed/external_module.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_embed/external_module.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_embed/test_interpreter.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_embed/test_interpreter.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_embed/test_interpreter.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_embed/test_interpreter.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_embed/test_trampoline.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_embed/test_trampoline.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_enum.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_enum.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_enum.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_enum.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_eval.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_eval.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_eval.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_eval.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_eval_call.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_eval_call.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_exceptions.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_exceptions.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_exceptions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_exceptions.h -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_exceptions.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_exceptions.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_factory_constructors.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_factory_constructors.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_factory_constructors.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_factory_constructors.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_gil_scoped.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_gil_scoped.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_gil_scoped.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_gil_scoped.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_iostream.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_iostream.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_iostream.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_iostream.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_kwargs_and_defaults.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_kwargs_and_defaults.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_kwargs_and_defaults.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_kwargs_and_defaults.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_local_bindings.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_local_bindings.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_local_bindings.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_local_bindings.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_methods_and_attributes.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_methods_and_attributes.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_methods_and_attributes.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_methods_and_attributes.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_modules.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_modules.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_modules.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_modules.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_multiple_inheritance.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_multiple_inheritance.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_multiple_inheritance.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_multiple_inheritance.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_numpy_array.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_numpy_array.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_numpy_array.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_numpy_array.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_numpy_dtypes.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_numpy_dtypes.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_numpy_dtypes.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_numpy_dtypes.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_numpy_vectorize.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_numpy_vectorize.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_numpy_vectorize.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_numpy_vectorize.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_opaque_types.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_opaque_types.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_opaque_types.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_opaque_types.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_operator_overloading.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_operator_overloading.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_operator_overloading.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_operator_overloading.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_pickling.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_pickling.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_pickling.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_pickling.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_pytypes.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_pytypes.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_pytypes.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_pytypes.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_sequences_and_iterators.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_sequences_and_iterators.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_sequences_and_iterators.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_sequences_and_iterators.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_smart_ptr.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_smart_ptr.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_smart_ptr.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_smart_ptr.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_stl.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_stl.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_stl.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_stl.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_stl_binders.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_stl_binders.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_stl_binders.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_stl_binders.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_tagbased_polymorphic.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_tagbased_polymorphic.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_tagbased_polymorphic.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_tagbased_polymorphic.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_thread.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_thread.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_thread.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_thread.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_type_caster_pyobject_ptr.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_type_caster_pyobject_ptr.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_union.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_union.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_union.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_union.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_unnamed_namespace_a.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_unnamed_namespace_a.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_unnamed_namespace_a.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_unnamed_namespace_a.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_unnamed_namespace_b.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_unnamed_namespace_b.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_unnamed_namespace_b.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_unnamed_namespace_b.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_vector_unique_ptr_member.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_vector_unique_ptr_member.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_virtual_functions.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_virtual_functions.cpp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/test_virtual_functions.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/test_virtual_functions.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/valgrind-numpy-scipy.supp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/valgrind-numpy-scipy.supp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tests/valgrind-python.supp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tests/valgrind-python.supp -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tools/FindCatch.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tools/FindCatch.cmake -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tools/FindEigen3.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tools/FindEigen3.cmake -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tools/FindPythonLibsNew.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tools/FindPythonLibsNew.cmake -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tools/JoinPaths.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tools/JoinPaths.cmake -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tools/check-style.sh: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tools/check-style.sh -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tools/cmake_uninstall.cmake.in: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tools/cmake_uninstall.cmake.in -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tools/libsize.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tools/libsize.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tools/make_changelog.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tools/make_changelog.py -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tools/pybind11.pc.in: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tools/pybind11.pc.in -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tools/pybind11Common.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tools/pybind11Common.cmake -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tools/pybind11Config.cmake.in: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tools/pybind11Config.cmake.in -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tools/pybind11NewTools.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tools/pybind11NewTools.cmake -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tools/pybind11Tools.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tools/pybind11Tools.cmake -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tools/pyproject.toml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tools/pyproject.toml -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tools/setup_global.py.in: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tools/setup_global.py.in -------------------------------------------------------------------------------- /third_party/go1_sdk/pybind11/tools/setup_main.py.in: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yxyang/jumping_cod/HEAD/third_party/go1_sdk/pybind11/tools/setup_main.py.in --------------------------------------------------------------------------------