├── .gitignore ├── .gitmodules ├── AddTextToImage ├── AddTextToImage.m ├── AddTextToImageDemo.m ├── AddTextToImageWithBorder.m ├── AddTextToImageWithBorderDemo.m ├── BitmapFont.m ├── RasterizeText.m └── license.txt ├── AssignmentProblem ├── auctionAlgorithmSparseMex.cpp ├── lapjv.m ├── lapjv_fast.m ├── munkres.m └── sparseAssignmentProblemAuctionAlgorithm.m ├── BayesianFilters ├── BinaryBayesFilter.m ├── Distributions │ ├── ConditionalGaussian.m │ ├── ConditionalNonlinearWithAdditiveGaussian.m │ ├── Gaussian.m │ ├── TestConditional.m │ ├── TestConditional2.m │ ├── TestProduct.m │ ├── TestTransform.m │ ├── TestUnscentedWithNoiseInput.m │ ├── Triangle.m │ ├── Uniform.m │ ├── numjacobian.m │ ├── numjacobian2_real.m │ ├── numjacobian_real.m │ ├── pdf_zeromean_gaussian.m │ ├── pdf_zeromean_triangle.m │ ├── rand_zeromean_gaussian_efficient.m │ └── rand_zeromean_triangle.m ├── Histogram.m ├── HistogramFilter.m ├── MomentPropagation.m ├── TestBayesRule.m ├── TestHistogram.m ├── TestHistogramFilter.m └── TestMomentMatching.m ├── CurveFitting ├── Algorithms.txt ├── BezierCurve.m ├── Bspline │ ├── BsplineFindProgress.m │ ├── BsplineFindProgressTest.m │ ├── Bspline_generic.m │ ├── Bspline_simple_closed.m │ ├── Bspline_uniform.m │ ├── FailingBsplineGetNearest.m │ ├── NURB_Curve.m │ ├── NURB_PixelSurface.m │ ├── NumericalArcCurveLength.m │ ├── TestBspline.m │ ├── TestBsplineFitting.m │ ├── Test_NURB_Surface.m │ └── map.png ├── Dubins │ ├── Dubins.m │ ├── DubinsDerivation_LRL.m │ ├── DubinsDerivation_RLR.m │ ├── DubinsTest.m │ ├── dubins_core.m │ └── dubins_curve.m ├── PiecewiseG1BezierFit │ ├── BezierFitDemo.m │ ├── LICENSE │ ├── NearestPoint.m │ ├── README.md │ ├── berny.m │ ├── bstdst.m │ ├── cpoints.m │ ├── ctpts.m │ ├── cubicBezierToPolyline.m │ ├── defk.m │ ├── distEJL.m │ ├── drawBezierCurve.m │ ├── drawPolyline.m │ ├── err.m │ ├── findClosestPoint.m │ ├── fndpts.m │ ├── foo │ ├── globop.m │ ├── iguess.m │ ├── iguess0.m │ ├── images │ │ ├── Continuity.jpg │ │ ├── Example1.png │ │ ├── Example2.png │ │ └── Example3.png │ ├── insrtkt.m │ ├── isAxisHandle.m │ ├── knots.m │ ├── ktangdt.m │ ├── newk.m │ ├── objf2.m │ ├── opdist.m │ ├── pltC.m │ ├── poplt.m │ ├── rmvkt.m │ ├── segop.m │ ├── sod.m │ ├── tang.m │ └── unitv.m ├── ReedsShepp │ ├── ReedsShepp.m │ └── ReedsSheppTest.m ├── Symbolic_CoxDeBoorRecursion.m ├── fitBezierCurve.m ├── fitCubicSpline.m ├── fitExponentialDecay.m ├── fitExponentialDecay2.m ├── fitNonlinearModel.m ├── fitNonlinearModelExample.m ├── testFitExponentialDecay2.m └── workspace.mat ├── DERIVESTsuite ├── ReadMe.rtf ├── demo │ ├── derivest_demo.m │ ├── html │ │ ├── derivest_demo.html │ │ ├── derivest_demo.png │ │ ├── derivest_demo_01.png │ │ └── multivariable_calc_demo.html │ └── multivariable_calc_demo.m ├── derivest.m ├── directionaldiff.m ├── doc │ ├── DERIVEST.pdf │ └── DERIVEST.tex ├── gradest.m ├── hessdiag.m ├── hessian.m └── jacobianest.m ├── FeatureExtractors ├── ORB │ ├── BRIEF.m │ ├── FAST_filter.m │ ├── GeometricTest.m │ ├── IMG_7894.JPG │ ├── IMG_7895.JPG │ ├── README.md │ ├── computeHomography.m │ ├── compute_reproj_error.m │ ├── fast9.m │ ├── findmatches.m │ ├── harris.m │ ├── homography.m │ ├── licence.txt │ ├── main.m │ ├── orb.m │ ├── orientation.m │ ├── rBRIEF.m │ ├── ransacIter.m │ ├── sampling_param.m │ ├── test1.jpeg │ └── test2.jpeg ├── OpenSURF │ ├── OpenSurf.m │ ├── SubFunctions │ │ ├── FastHessian_BuildDerivative.m │ │ ├── FastHessian_ResponseLayer.m │ │ ├── FastHessian_buildResponseLayer.m │ │ ├── FastHessian_buildResponseMap.m │ │ ├── FastHessian_getIpoints.m │ │ ├── FastHessian_getLaplacian.m │ │ ├── FastHessian_getResponse.m │ │ ├── FastHessian_interpolateExtremum.m │ │ ├── FastHessian_isExtremum.m │ │ ├── IntegralImage_BoxIntegral.m │ │ ├── IntegralImage_HaarX.m │ │ ├── IntegralImage_HaarY.m │ │ ├── IntegralImage_IntegralImage.m │ │ ├── PaintSURF.m │ │ ├── SurfDescriptor_DecribeInterestPoints.m │ │ ├── SurfDescriptor_GetDescriptor.m │ │ └── SurfDescriptor_GetOrientation.m │ ├── TestImages │ │ ├── lena1.png │ │ ├── lena2.png │ │ ├── test.png │ │ ├── testc1.png │ │ └── testc2.png │ ├── WarpFunctions │ │ └── affine_warp.m │ ├── example2.m │ ├── example3.m │ └── license.txt ├── SIFT │ ├── IMG_7894.JPG │ ├── IMG_7895.JPG │ ├── SIFT_feature.m │ └── license.txt └── siftDemoV4 │ ├── LICENSE │ ├── Makefile │ ├── README │ ├── appendimages.m │ ├── basmati.pgm │ ├── book.pgm │ ├── box.pgm │ ├── defs.h │ ├── match.c │ ├── match.m │ ├── scene.pgm │ ├── showkeys.m │ ├── sift │ ├── sift.m │ └── util.c ├── FloatingPointLogarithm.m ├── FrequencyAnalysis └── plotFFT.m ├── Geometry ├── HeadingIntersection.m ├── LineIntersection.m ├── TEST_findClosestPoint.m └── findClosestPoint.m ├── Graph └── graph_conn_comp.m ├── ICP ├── ICP methods.txt ├── ICPmanu_allign2.m ├── Preall.m ├── icp.m ├── minimize_point_to_plane.m └── rigidICP.m ├── ImageProcessing ├── CircleHoughTransform.m ├── bwlabel.m ├── bwlabel_count.m ├── dilate.m ├── erode.m ├── license.txt └── line_drawing_raytracing.m ├── KalmanFilters ├── CKF.m ├── EIF.m ├── EKF.m ├── IEKF.m ├── IF.m ├── IteratedEKF.m ├── KF.m ├── MeasurementModels │ ├── GyroscopeSensor.m │ ├── MeasurementModelHandler.m │ ├── PositionSensor.m │ ├── PositionSensor2D.m │ ├── RangeBearingSensor.m │ └── VelocitySensor.m ├── MotionModels │ ├── BicycleModel_Continuous.m │ ├── BicycleModel_Discrete.m │ ├── ConstantAcceleration2D_Continuous.m │ ├── ConstantAcceleration_Continuous.m │ ├── ConstantVelocity2D_Continuous.m │ ├── ConstantVelocity2D_Discrete.m │ ├── ConstantVelocity_Continuous.m │ ├── ConstantVelocity_Discrete.m │ ├── ContinuousMotionModelHandler.m │ ├── CoordinatedTurnModel_Continuous.m │ ├── CoordinatedTurnModel_Discrete.m │ ├── CoordinatedTurnModel_Discrete2.m │ ├── CoordinatedTurnModel_Discrete_Thrun.m │ ├── DiscreteMotionModelHandler.m │ ├── TestCoordinatedTurnModel_Discrete_Thrun.m │ └── UnicycleModel_Continuous.m ├── Tests │ ├── MotionModelJacobianComparison.m │ ├── TestEIF.m │ ├── TestEKF.m │ ├── TestKF2.m │ └── TestUKF.m ├── UKF.m ├── discretize_analytic.m ├── discretize_bilinear.m ├── discretize_euler.m ├── discretize_matexp.m ├── numjacobian.m ├── numjacobian2.m └── numjacobian3.m ├── LICENSE ├── LeastSquares ├── Line.m ├── Line2.m ├── LinearLeastSquares.m ├── Plane.m ├── Plane2.m ├── Plane3.m ├── RecursiveLeastSquares.m ├── RecursiveLeastSquares_1D.m ├── RecursiveLeastSquares_2D.m ├── RecursiveLeastSquares_KF.m └── RunningAverage.m ├── MATLAB to Point Cloud Library ├── README ├── license.txt ├── loadpcd.m ├── lspcd.m ├── lzfd.m ├── pclviewer.m ├── resources │ ├── addons_core.xml │ ├── matlab_path_entries.xml │ ├── matpcl.zip │ ├── metadata.xml │ ├── previewImage.png │ └── screenshot.png └── savepcd.m ├── MachineLearning └── HMM │ ├── DiscreteHMM │ ├── demo.m │ ├── discreteRnd.m │ ├── hmmEm.m │ ├── hmmFilter.m │ ├── hmmFilter_.m │ ├── hmmRnd.m │ ├── hmmSmoother.m │ ├── hmmSmoother_.m │ ├── hmmViterbi.m │ ├── hmmViterbi_.m │ ├── license.txt │ └── normalize.m │ └── GaussianHMM │ ├── em_ghmm.c │ ├── forward_backward.c │ ├── license.txt │ ├── likelihood_mvgm.c │ ├── mexme_em_ghmm.m │ ├── ndellipse.c │ ├── sample_ghmm.c │ └── test_em_ghmm.m ├── Madgwick ├── @MadgwickAHRS │ └── MadgwickAHRS.m ├── @MahonyAHRS │ └── MahonyAHRS.m ├── ExampleScript.m ├── LICENSE └── quaternion_library │ ├── TestScript.m │ ├── axisAngle2quatern.m │ ├── axisAngle2rotMat.m │ ├── euler2rotMat.m │ ├── quatern2euler.m │ ├── quatern2rotMat.m │ ├── quaternConj.m │ ├── quaternProd.m │ ├── rotMat2euler.m │ └── rotMat2quatern.m ├── Mapping ├── AMCL.m ├── AMCL2.m ├── BeamRangeSensor.m ├── CarSim.m ├── OccupancyGrid │ └── OccupancyGrid.m ├── ScanICP.m ├── TestAMCL.m ├── TestBeamRangeSensor.m ├── TestOccupancyMapping.m ├── TestScanMatching.m ├── example.bmp ├── straight.bmp ├── straight2.bmp └── straight3.bmp ├── Optimization ├── GraphOptimization │ └── To Do.txt ├── LevenbergMarquardt │ ├── ExampleWithAndWithoutJacobian.m │ ├── Example_nested_contraction.m │ ├── LMFnlsq │ │ ├── LMFnlsq.m │ │ ├── LMFnlsqtest.m │ │ ├── LMFnlsqtest.pdf │ │ ├── license.txt │ │ └── res.m │ ├── LMFsolve │ │ ├── LMFsolve.m │ │ ├── LMFsolveOLD.m │ │ ├── LMFsolvetest.m │ │ ├── license.txt │ │ └── rosen.m │ ├── LMsimple │ │ ├── lm.m │ │ ├── lm_examp.m │ │ ├── lm_func.m │ │ └── lm_plots.m │ ├── LevenbergMarquardt.m │ ├── license.txt │ └── nested_contraction_obj.m ├── NonlinearOptimizers.m ├── TestNonlinearOptimizers.m ├── jacobianext.m ├── jacobianlim.m ├── jacobiansimple.m ├── license.txt └── numjacobian.m ├── PCD ├── MATLAB to Point Cloud Library - File Exchange - MATLAB Central.desktop ├── boxFilter.m ├── combinePCD.m ├── enablePCDtooltip.m ├── extractPCD.m ├── getBoundingBox.m ├── loadPCD.m ├── loadpcd_auto.m ├── loadpcd_raw.m ├── pcdHeader.m ├── plotPCD.m ├── plotTransform.m ├── plotValues.m ├── removeFromPCD.m ├── rotatePCD.m ├── savepcd.m ├── savepcdOld.m ├── sortPCD.m └── transformPCD.m ├── ParticleFilters ├── BootstrapFilter │ ├── AdaptiveParticleFilter.m │ ├── BootstrapFilter.m │ ├── BootstrapSISFilter.m │ ├── ImportanceSampling_WeightedSamples.m │ ├── ImprovedSIRFilter.m │ ├── SIRFilter.m │ ├── TestFilter.m │ └── TestImportanceSampling.m ├── MPF │ ├── experiment.m │ ├── mpf.m │ ├── pf.m │ └── sysresample.m └── RaoBlackwellizedPF │ ├── RaoBlackwellizedPF.m │ ├── RaoBlackwellizedParticle.m │ └── TestRaoBlackwellizedPF.m ├── Planning └── GraphAlgorithms │ ├── DijkstraAstarTest.m │ ├── NonHolonomicPlanning.m │ ├── PriorityQueue │ ├── PriorityQueue.m │ └── license.txt │ ├── PriorityQueue2.m │ ├── Robot.m │ └── track.png ├── Quaternion ├── ExtractHeading.m ├── Gamma.m ├── HeadingErrorWrapping.m ├── HeadingIndependentReference.m ├── HeadingQuaternion.m ├── Phi.m ├── Quaternion2ZYXEulerAngles.m ├── QuaternionError.m ├── QuaternionNoiseCovarianceMatrix.m ├── QuaternionPropagationWithBias.m ├── QuaternionTransitionMatrix.m ├── ZYXEulerAngles2Quaternion.m ├── axang2quat.m ├── eul2quat.m ├── matrix2quaternion.m ├── omega_b2qdot.m ├── q2tr.m ├── qdevec.m ├── qdot2omega_b.m ├── quat2angle.m ├── quat2axang.m ├── quat2eul.m ├── quat2rotm.m ├── quatconj.m ├── quatexp.m ├── quatinv.m ├── quatlogn.m ├── quatmod.m ├── quatmul.m ├── quatmultiply.m ├── quatnorm.m ├── quatnormalize.m ├── quatpow.m ├── quatslerp.m ├── quatslerp2.m ├── qvec.m ├── rotm2quat.m ├── rvec2quat.m ├── tr2q.m ├── unwrapangle.m ├── unwrapstep.m ├── wrapTo2Pi.m └── wrapToPi.m ├── README.md ├── ReplaceStringInFile.m ├── RotationMatrix ├── SpinCalc.m ├── eul2rotm.m ├── rot2.m ├── rotationBetweenVectors.m ├── rotm2eul.m ├── rotm2heading.m ├── rotm2tf.m ├── rotx.m ├── roty.m ├── rotz.m ├── tf2heading.m ├── tf2rotm.m ├── trotx.m ├── troty.m └── trotz.m ├── ScanMatching ├── GitHub_szandara-2DScanMatching.url ├── ICP2D.m ├── See also ICP folder.txt ├── Test2D_ICP.m ├── Test2DscanMatching.m ├── registerCensi.m ├── registerLSQ.m └── registerSVD.m ├── Statistics ├── betacdf.m ├── betainv.m ├── betapdf.m ├── betarnd.m ├── chi2cdf.m ├── chi2inv.m ├── exprnd.m ├── gamcdf.m ├── gaminv.m ├── gampdf.m ├── gamrnd.m ├── normcdf.m ├── normcdf2.m ├── norminv.m ├── normpdf.m ├── normrnd.m ├── stdnormal_cdf.m ├── stdnormal_inv.m ├── stdnormal_pdf.m ├── tcdf.m ├── tinv.m ├── tpdf.m ├── trnd.m ├── tstat.m ├── wblcdf.m ├── wblinv.m └── wblrnd.m ├── TimeSeries ├── Downsample.m ├── Extract.m ├── Trim.m └── findMatchingIndex.m ├── Tracking └── SOT │ └── GroundtruthGenerator.m ├── absor.m ├── atan2_approximation.m ├── bestblk.m ├── bin2float.m ├── circle.m ├── colorPlot2D.m ├── colorPlot3D.m ├── columns.m ├── corrcoef ├── corrcoef.m ├── flag_implicit_skip_nan.m ├── sumskipnan.m └── tcdf.m ├── csvwrite_with_headers.m ├── fitmethis.m ├── float2bin.m ├── getUnixTimestampsFromFilenames.m ├── getdatesortedfiles.m ├── getlatestfile.m ├── hline.m ├── immarker.m ├── imresize.m ├── isfile2.m ├── isgray.m ├── isint.m ├── isnum.m ├── isrow2.m ├── issquare.m ├── jetColor.m ├── jetColorLUT.m ├── mod2pi.m ├── nanmean.m ├── nearestneighbour ├── demo │ ├── html │ │ ├── nndemo.html │ │ ├── nndemo.png │ │ ├── nndemo_01.png │ │ ├── nndemo_02.png │ │ ├── nndemo_03.png │ │ └── nndemo_04.png │ ├── nndemo.m │ ├── nndemo.mlx │ └── timingtest.m ├── license.txt └── nearestneighbour.m ├── ordeig2.m ├── plotfitdist.m ├── principalValue.m ├── rows.m ├── saveImage.m ├── smooth.m ├── startup.m ├── stats-matlab ├── common_size.m ├── corr.m └── quantile.m ├── strsplit ├── private │ ├── ischarint.m │ └── ischarnum.m └── strsplit.m ├── struct2array.m ├── timestampFromFilename.m ├── utilities ├── axang2quat.m ├── axang2rotm.m ├── baseVel2params.m ├── deul.m ├── deul2angVel.m ├── dquat.m ├── eul2angRateTF.m ├── eul2angVelTF.m ├── eul2quat.m ├── eul2rotm.m ├── fastForwardDynamics.m ├── fastGetStateParams.m ├── fastIntForwardDynamics.m ├── fileExist.m ├── frame2posEul.m ├── frame2posRotm.m ├── frame2tform.m ├── generalizedBaseAcc.m ├── getJointAnnotationICub.m ├── getJointNamesFromURDF.m ├── getSimConfigFromURDF.m ├── initJointsFromNameList.m ├── isHomog.m ├── isNormalized.m ├── isRadians.m ├── isStateEmpty.m ├── params2rotoTrans.m ├── params2stateVec.m ├── plotquat.m ├── posRotm2tform.m ├── quat2axang.m ├── quat2eul.m ├── quat2rotm.m ├── quat2tform.m ├── quatconj.m ├── quatdiv.m ├── quatinv.m ├── quatmagnitude.m ├── quatmult.m ├── quatnorm.m ├── quatnormalize.m ├── quatslerp.m ├── rotm2axang.m ├── rotm2eul.m ├── rotm2eulAngVelTF.m ├── rotm2quat.m ├── rotx.m ├── roty.m ├── rotz.m ├── skewm.m ├── skewm2vec.m ├── tform2angRateTF.m ├── tform2angVelTF.m ├── tform2axang.m ├── tform2eul.m ├── tform2frame.m ├── tform2posRotm.m └── tform2quat.m ├── vec.m └── vline.m /.gitignore: -------------------------------------------------------------------------------- 1 | *.asv -------------------------------------------------------------------------------- /.gitmodules: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /AddTextToImage/AddTextToImage.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/AddTextToImage/AddTextToImage.m -------------------------------------------------------------------------------- /AddTextToImage/AddTextToImageDemo.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/AddTextToImage/AddTextToImageDemo.m -------------------------------------------------------------------------------- /AddTextToImage/AddTextToImageWithBorder.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/AddTextToImage/AddTextToImageWithBorder.m -------------------------------------------------------------------------------- /AddTextToImage/AddTextToImageWithBorderDemo.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/AddTextToImage/AddTextToImageWithBorderDemo.m -------------------------------------------------------------------------------- /AddTextToImage/BitmapFont.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/AddTextToImage/BitmapFont.m -------------------------------------------------------------------------------- /AddTextToImage/RasterizeText.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/AddTextToImage/RasterizeText.m -------------------------------------------------------------------------------- /AddTextToImage/license.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/AddTextToImage/license.txt -------------------------------------------------------------------------------- /AssignmentProblem/auctionAlgorithmSparseMex.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/AssignmentProblem/auctionAlgorithmSparseMex.cpp -------------------------------------------------------------------------------- /AssignmentProblem/lapjv.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/AssignmentProblem/lapjv.m -------------------------------------------------------------------------------- /AssignmentProblem/lapjv_fast.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/AssignmentProblem/lapjv_fast.m -------------------------------------------------------------------------------- /AssignmentProblem/munkres.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/AssignmentProblem/munkres.m -------------------------------------------------------------------------------- /AssignmentProblem/sparseAssignmentProblemAuctionAlgorithm.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/AssignmentProblem/sparseAssignmentProblemAuctionAlgorithm.m -------------------------------------------------------------------------------- /BayesianFilters/BinaryBayesFilter.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/BinaryBayesFilter.m -------------------------------------------------------------------------------- /BayesianFilters/Distributions/ConditionalGaussian.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/Distributions/ConditionalGaussian.m -------------------------------------------------------------------------------- /BayesianFilters/Distributions/ConditionalNonlinearWithAdditiveGaussian.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/Distributions/ConditionalNonlinearWithAdditiveGaussian.m -------------------------------------------------------------------------------- /BayesianFilters/Distributions/Gaussian.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/Distributions/Gaussian.m -------------------------------------------------------------------------------- /BayesianFilters/Distributions/TestConditional.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/Distributions/TestConditional.m -------------------------------------------------------------------------------- /BayesianFilters/Distributions/TestConditional2.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/Distributions/TestConditional2.m -------------------------------------------------------------------------------- /BayesianFilters/Distributions/TestProduct.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/Distributions/TestProduct.m -------------------------------------------------------------------------------- /BayesianFilters/Distributions/TestTransform.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/Distributions/TestTransform.m -------------------------------------------------------------------------------- /BayesianFilters/Distributions/TestUnscentedWithNoiseInput.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/Distributions/TestUnscentedWithNoiseInput.m -------------------------------------------------------------------------------- /BayesianFilters/Distributions/Triangle.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/Distributions/Triangle.m -------------------------------------------------------------------------------- /BayesianFilters/Distributions/Uniform.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/Distributions/Uniform.m -------------------------------------------------------------------------------- /BayesianFilters/Distributions/numjacobian.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/Distributions/numjacobian.m -------------------------------------------------------------------------------- /BayesianFilters/Distributions/numjacobian2_real.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/Distributions/numjacobian2_real.m -------------------------------------------------------------------------------- /BayesianFilters/Distributions/numjacobian_real.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/Distributions/numjacobian_real.m -------------------------------------------------------------------------------- /BayesianFilters/Distributions/pdf_zeromean_gaussian.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/Distributions/pdf_zeromean_gaussian.m -------------------------------------------------------------------------------- /BayesianFilters/Distributions/pdf_zeromean_triangle.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/Distributions/pdf_zeromean_triangle.m -------------------------------------------------------------------------------- /BayesianFilters/Distributions/rand_zeromean_gaussian_efficient.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/Distributions/rand_zeromean_gaussian_efficient.m -------------------------------------------------------------------------------- /BayesianFilters/Distributions/rand_zeromean_triangle.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/Distributions/rand_zeromean_triangle.m -------------------------------------------------------------------------------- /BayesianFilters/Histogram.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/Histogram.m -------------------------------------------------------------------------------- /BayesianFilters/HistogramFilter.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/HistogramFilter.m -------------------------------------------------------------------------------- /BayesianFilters/MomentPropagation.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/MomentPropagation.m -------------------------------------------------------------------------------- /BayesianFilters/TestBayesRule.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/TestBayesRule.m -------------------------------------------------------------------------------- /BayesianFilters/TestHistogram.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/TestHistogram.m -------------------------------------------------------------------------------- /BayesianFilters/TestHistogramFilter.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/TestHistogramFilter.m -------------------------------------------------------------------------------- /BayesianFilters/TestMomentMatching.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/BayesianFilters/TestMomentMatching.m -------------------------------------------------------------------------------- /CurveFitting/Algorithms.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Algorithms.txt -------------------------------------------------------------------------------- /CurveFitting/BezierCurve.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/BezierCurve.m -------------------------------------------------------------------------------- /CurveFitting/Bspline/BsplineFindProgress.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Bspline/BsplineFindProgress.m -------------------------------------------------------------------------------- /CurveFitting/Bspline/BsplineFindProgressTest.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Bspline/BsplineFindProgressTest.m -------------------------------------------------------------------------------- /CurveFitting/Bspline/Bspline_generic.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Bspline/Bspline_generic.m -------------------------------------------------------------------------------- /CurveFitting/Bspline/Bspline_simple_closed.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Bspline/Bspline_simple_closed.m -------------------------------------------------------------------------------- /CurveFitting/Bspline/Bspline_uniform.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Bspline/Bspline_uniform.m -------------------------------------------------------------------------------- /CurveFitting/Bspline/FailingBsplineGetNearest.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Bspline/FailingBsplineGetNearest.m -------------------------------------------------------------------------------- /CurveFitting/Bspline/NURB_Curve.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Bspline/NURB_Curve.m -------------------------------------------------------------------------------- /CurveFitting/Bspline/NURB_PixelSurface.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Bspline/NURB_PixelSurface.m -------------------------------------------------------------------------------- /CurveFitting/Bspline/NumericalArcCurveLength.m: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /CurveFitting/Bspline/TestBspline.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Bspline/TestBspline.m -------------------------------------------------------------------------------- /CurveFitting/Bspline/TestBsplineFitting.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Bspline/TestBsplineFitting.m -------------------------------------------------------------------------------- /CurveFitting/Bspline/Test_NURB_Surface.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Bspline/Test_NURB_Surface.m -------------------------------------------------------------------------------- /CurveFitting/Bspline/map.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Bspline/map.png -------------------------------------------------------------------------------- /CurveFitting/Dubins/Dubins.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Dubins/Dubins.m -------------------------------------------------------------------------------- /CurveFitting/Dubins/DubinsDerivation_LRL.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Dubins/DubinsDerivation_LRL.m -------------------------------------------------------------------------------- /CurveFitting/Dubins/DubinsDerivation_RLR.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Dubins/DubinsDerivation_RLR.m -------------------------------------------------------------------------------- /CurveFitting/Dubins/DubinsTest.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Dubins/DubinsTest.m -------------------------------------------------------------------------------- /CurveFitting/Dubins/dubins_core.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Dubins/dubins_core.m -------------------------------------------------------------------------------- /CurveFitting/Dubins/dubins_curve.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Dubins/dubins_curve.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/BezierFitDemo.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/BezierFitDemo.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/LICENSE -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/NearestPoint.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/NearestPoint.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/README.md -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/berny.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/berny.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/bstdst.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/bstdst.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/cpoints.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/cpoints.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/ctpts.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/ctpts.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/cubicBezierToPolyline.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/cubicBezierToPolyline.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/defk.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/defk.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/distEJL.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/distEJL.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/drawBezierCurve.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/drawBezierCurve.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/drawPolyline.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/drawPolyline.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/err.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/err.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/findClosestPoint.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/findClosestPoint.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/fndpts.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/fndpts.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/foo: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/foo -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/globop.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/globop.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/iguess.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/iguess.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/iguess0.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/iguess0.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/images/Continuity.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/images/Continuity.jpg -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/images/Example1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/images/Example1.png -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/images/Example2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/images/Example2.png -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/images/Example3.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/images/Example3.png -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/insrtkt.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/insrtkt.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/isAxisHandle.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/isAxisHandle.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/knots.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/knots.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/ktangdt.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/ktangdt.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/newk.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/newk.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/objf2.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/objf2.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/opdist.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/opdist.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/pltC.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/pltC.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/poplt.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/poplt.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/rmvkt.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/rmvkt.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/segop.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/segop.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/sod.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/sod.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/tang.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/tang.m -------------------------------------------------------------------------------- /CurveFitting/PiecewiseG1BezierFit/unitv.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/PiecewiseG1BezierFit/unitv.m -------------------------------------------------------------------------------- /CurveFitting/ReedsShepp/ReedsShepp.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/ReedsShepp/ReedsShepp.m -------------------------------------------------------------------------------- /CurveFitting/ReedsShepp/ReedsSheppTest.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/ReedsShepp/ReedsSheppTest.m -------------------------------------------------------------------------------- /CurveFitting/Symbolic_CoxDeBoorRecursion.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/Symbolic_CoxDeBoorRecursion.m -------------------------------------------------------------------------------- /CurveFitting/fitBezierCurve.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/fitBezierCurve.m -------------------------------------------------------------------------------- /CurveFitting/fitCubicSpline.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/fitCubicSpline.m -------------------------------------------------------------------------------- /CurveFitting/fitExponentialDecay.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/fitExponentialDecay.m -------------------------------------------------------------------------------- /CurveFitting/fitExponentialDecay2.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/fitExponentialDecay2.m -------------------------------------------------------------------------------- /CurveFitting/fitNonlinearModel.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/fitNonlinearModel.m -------------------------------------------------------------------------------- /CurveFitting/fitNonlinearModelExample.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/fitNonlinearModelExample.m -------------------------------------------------------------------------------- /CurveFitting/testFitExponentialDecay2.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/testFitExponentialDecay2.m -------------------------------------------------------------------------------- /CurveFitting/workspace.mat: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/CurveFitting/workspace.mat -------------------------------------------------------------------------------- /DERIVESTsuite/ReadMe.rtf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/DERIVESTsuite/ReadMe.rtf -------------------------------------------------------------------------------- /DERIVESTsuite/demo/derivest_demo.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/DERIVESTsuite/demo/derivest_demo.m -------------------------------------------------------------------------------- /DERIVESTsuite/demo/html/derivest_demo.html: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/DERIVESTsuite/demo/html/derivest_demo.html -------------------------------------------------------------------------------- /DERIVESTsuite/demo/html/derivest_demo.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/DERIVESTsuite/demo/html/derivest_demo.png -------------------------------------------------------------------------------- /DERIVESTsuite/demo/html/derivest_demo_01.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/DERIVESTsuite/demo/html/derivest_demo_01.png -------------------------------------------------------------------------------- /DERIVESTsuite/demo/html/multivariable_calc_demo.html: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/DERIVESTsuite/demo/html/multivariable_calc_demo.html -------------------------------------------------------------------------------- /DERIVESTsuite/demo/multivariable_calc_demo.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/DERIVESTsuite/demo/multivariable_calc_demo.m -------------------------------------------------------------------------------- /DERIVESTsuite/derivest.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/DERIVESTsuite/derivest.m -------------------------------------------------------------------------------- /DERIVESTsuite/directionaldiff.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/DERIVESTsuite/directionaldiff.m -------------------------------------------------------------------------------- /DERIVESTsuite/doc/DERIVEST.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/DERIVESTsuite/doc/DERIVEST.pdf -------------------------------------------------------------------------------- /DERIVESTsuite/doc/DERIVEST.tex: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/DERIVESTsuite/doc/DERIVEST.tex -------------------------------------------------------------------------------- /DERIVESTsuite/gradest.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/DERIVESTsuite/gradest.m -------------------------------------------------------------------------------- /DERIVESTsuite/hessdiag.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/DERIVESTsuite/hessdiag.m -------------------------------------------------------------------------------- /DERIVESTsuite/hessian.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/DERIVESTsuite/hessian.m -------------------------------------------------------------------------------- /DERIVESTsuite/jacobianest.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/DERIVESTsuite/jacobianest.m -------------------------------------------------------------------------------- /FeatureExtractors/ORB/BRIEF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/BRIEF.m -------------------------------------------------------------------------------- /FeatureExtractors/ORB/FAST_filter.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/FAST_filter.m -------------------------------------------------------------------------------- /FeatureExtractors/ORB/GeometricTest.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/GeometricTest.m -------------------------------------------------------------------------------- /FeatureExtractors/ORB/IMG_7894.JPG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/IMG_7894.JPG -------------------------------------------------------------------------------- /FeatureExtractors/ORB/IMG_7895.JPG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/IMG_7895.JPG -------------------------------------------------------------------------------- /FeatureExtractors/ORB/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/README.md -------------------------------------------------------------------------------- /FeatureExtractors/ORB/computeHomography.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/computeHomography.m -------------------------------------------------------------------------------- /FeatureExtractors/ORB/compute_reproj_error.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/compute_reproj_error.m -------------------------------------------------------------------------------- /FeatureExtractors/ORB/fast9.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/fast9.m -------------------------------------------------------------------------------- /FeatureExtractors/ORB/findmatches.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/findmatches.m -------------------------------------------------------------------------------- /FeatureExtractors/ORB/harris.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/harris.m -------------------------------------------------------------------------------- /FeatureExtractors/ORB/homography.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/homography.m -------------------------------------------------------------------------------- /FeatureExtractors/ORB/licence.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/licence.txt -------------------------------------------------------------------------------- /FeatureExtractors/ORB/main.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/main.m -------------------------------------------------------------------------------- /FeatureExtractors/ORB/orb.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/orb.m -------------------------------------------------------------------------------- /FeatureExtractors/ORB/orientation.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/orientation.m -------------------------------------------------------------------------------- /FeatureExtractors/ORB/rBRIEF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/rBRIEF.m -------------------------------------------------------------------------------- /FeatureExtractors/ORB/ransacIter.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/ransacIter.m -------------------------------------------------------------------------------- /FeatureExtractors/ORB/sampling_param.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/sampling_param.m -------------------------------------------------------------------------------- /FeatureExtractors/ORB/test1.jpeg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/test1.jpeg -------------------------------------------------------------------------------- /FeatureExtractors/ORB/test2.jpeg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/ORB/test2.jpeg -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/OpenSurf.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/OpenSurf.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/SubFunctions/FastHessian_BuildDerivative.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/SubFunctions/FastHessian_BuildDerivative.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/SubFunctions/FastHessian_ResponseLayer.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/SubFunctions/FastHessian_ResponseLayer.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/SubFunctions/FastHessian_buildResponseLayer.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/SubFunctions/FastHessian_buildResponseLayer.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/SubFunctions/FastHessian_buildResponseMap.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/SubFunctions/FastHessian_buildResponseMap.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/SubFunctions/FastHessian_getIpoints.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/SubFunctions/FastHessian_getIpoints.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/SubFunctions/FastHessian_getLaplacian.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/SubFunctions/FastHessian_getLaplacian.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/SubFunctions/FastHessian_getResponse.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/SubFunctions/FastHessian_getResponse.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/SubFunctions/FastHessian_interpolateExtremum.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/SubFunctions/FastHessian_interpolateExtremum.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/SubFunctions/FastHessian_isExtremum.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/SubFunctions/FastHessian_isExtremum.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/SubFunctions/IntegralImage_BoxIntegral.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/SubFunctions/IntegralImage_BoxIntegral.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/SubFunctions/IntegralImage_HaarX.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/SubFunctions/IntegralImage_HaarX.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/SubFunctions/IntegralImage_HaarY.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/SubFunctions/IntegralImage_HaarY.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/SubFunctions/IntegralImage_IntegralImage.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/SubFunctions/IntegralImage_IntegralImage.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/SubFunctions/PaintSURF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/SubFunctions/PaintSURF.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/SubFunctions/SurfDescriptor_DecribeInterestPoints.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/SubFunctions/SurfDescriptor_DecribeInterestPoints.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/SubFunctions/SurfDescriptor_GetDescriptor.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/SubFunctions/SurfDescriptor_GetDescriptor.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/SubFunctions/SurfDescriptor_GetOrientation.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/SubFunctions/SurfDescriptor_GetOrientation.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/TestImages/lena1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/TestImages/lena1.png -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/TestImages/lena2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/TestImages/lena2.png -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/TestImages/test.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/TestImages/test.png -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/TestImages/testc1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/TestImages/testc1.png -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/TestImages/testc2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/TestImages/testc2.png -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/WarpFunctions/affine_warp.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/WarpFunctions/affine_warp.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/example2.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/example2.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/example3.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/example3.m -------------------------------------------------------------------------------- /FeatureExtractors/OpenSURF/license.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/OpenSURF/license.txt -------------------------------------------------------------------------------- /FeatureExtractors/SIFT/IMG_7894.JPG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/SIFT/IMG_7894.JPG -------------------------------------------------------------------------------- /FeatureExtractors/SIFT/IMG_7895.JPG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/SIFT/IMG_7895.JPG -------------------------------------------------------------------------------- /FeatureExtractors/SIFT/SIFT_feature.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/SIFT/SIFT_feature.m -------------------------------------------------------------------------------- /FeatureExtractors/SIFT/license.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/SIFT/license.txt -------------------------------------------------------------------------------- /FeatureExtractors/siftDemoV4/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/siftDemoV4/LICENSE -------------------------------------------------------------------------------- /FeatureExtractors/siftDemoV4/Makefile: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/siftDemoV4/Makefile -------------------------------------------------------------------------------- /FeatureExtractors/siftDemoV4/README: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/siftDemoV4/README -------------------------------------------------------------------------------- /FeatureExtractors/siftDemoV4/appendimages.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/siftDemoV4/appendimages.m -------------------------------------------------------------------------------- /FeatureExtractors/siftDemoV4/basmati.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/siftDemoV4/basmati.pgm -------------------------------------------------------------------------------- /FeatureExtractors/siftDemoV4/book.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/siftDemoV4/book.pgm -------------------------------------------------------------------------------- /FeatureExtractors/siftDemoV4/box.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/siftDemoV4/box.pgm -------------------------------------------------------------------------------- /FeatureExtractors/siftDemoV4/defs.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/siftDemoV4/defs.h -------------------------------------------------------------------------------- /FeatureExtractors/siftDemoV4/match.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/siftDemoV4/match.c -------------------------------------------------------------------------------- /FeatureExtractors/siftDemoV4/match.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/siftDemoV4/match.m -------------------------------------------------------------------------------- /FeatureExtractors/siftDemoV4/scene.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/siftDemoV4/scene.pgm -------------------------------------------------------------------------------- /FeatureExtractors/siftDemoV4/showkeys.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/siftDemoV4/showkeys.m -------------------------------------------------------------------------------- /FeatureExtractors/siftDemoV4/sift: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/siftDemoV4/sift -------------------------------------------------------------------------------- /FeatureExtractors/siftDemoV4/sift.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/siftDemoV4/sift.m -------------------------------------------------------------------------------- /FeatureExtractors/siftDemoV4/util.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FeatureExtractors/siftDemoV4/util.c -------------------------------------------------------------------------------- /FloatingPointLogarithm.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FloatingPointLogarithm.m -------------------------------------------------------------------------------- /FrequencyAnalysis/plotFFT.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/FrequencyAnalysis/plotFFT.m -------------------------------------------------------------------------------- /Geometry/HeadingIntersection.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Geometry/HeadingIntersection.m -------------------------------------------------------------------------------- /Geometry/LineIntersection.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Geometry/LineIntersection.m -------------------------------------------------------------------------------- /Geometry/TEST_findClosestPoint.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Geometry/TEST_findClosestPoint.m -------------------------------------------------------------------------------- /Geometry/findClosestPoint.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Geometry/findClosestPoint.m -------------------------------------------------------------------------------- /Graph/graph_conn_comp.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Graph/graph_conn_comp.m -------------------------------------------------------------------------------- /ICP/ICP methods.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ICP/ICP methods.txt -------------------------------------------------------------------------------- /ICP/ICPmanu_allign2.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ICP/ICPmanu_allign2.m -------------------------------------------------------------------------------- /ICP/Preall.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ICP/Preall.m -------------------------------------------------------------------------------- /ICP/icp.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ICP/icp.m -------------------------------------------------------------------------------- /ICP/minimize_point_to_plane.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ICP/minimize_point_to_plane.m -------------------------------------------------------------------------------- /ICP/rigidICP.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ICP/rigidICP.m -------------------------------------------------------------------------------- /ImageProcessing/CircleHoughTransform.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ImageProcessing/CircleHoughTransform.m -------------------------------------------------------------------------------- /ImageProcessing/bwlabel.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ImageProcessing/bwlabel.m -------------------------------------------------------------------------------- /ImageProcessing/bwlabel_count.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ImageProcessing/bwlabel_count.m -------------------------------------------------------------------------------- /ImageProcessing/dilate.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ImageProcessing/dilate.m -------------------------------------------------------------------------------- /ImageProcessing/erode.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ImageProcessing/erode.m -------------------------------------------------------------------------------- /ImageProcessing/license.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ImageProcessing/license.txt -------------------------------------------------------------------------------- /ImageProcessing/line_drawing_raytracing.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ImageProcessing/line_drawing_raytracing.m -------------------------------------------------------------------------------- /KalmanFilters/CKF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/CKF.m -------------------------------------------------------------------------------- /KalmanFilters/EIF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/EIF.m -------------------------------------------------------------------------------- /KalmanFilters/EKF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/EKF.m -------------------------------------------------------------------------------- /KalmanFilters/IEKF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/IEKF.m -------------------------------------------------------------------------------- /KalmanFilters/IF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/IF.m -------------------------------------------------------------------------------- /KalmanFilters/IteratedEKF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/IteratedEKF.m -------------------------------------------------------------------------------- /KalmanFilters/KF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/KF.m -------------------------------------------------------------------------------- /KalmanFilters/MeasurementModels/GyroscopeSensor.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MeasurementModels/GyroscopeSensor.m -------------------------------------------------------------------------------- /KalmanFilters/MeasurementModels/MeasurementModelHandler.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MeasurementModels/MeasurementModelHandler.m -------------------------------------------------------------------------------- /KalmanFilters/MeasurementModels/PositionSensor.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MeasurementModels/PositionSensor.m -------------------------------------------------------------------------------- /KalmanFilters/MeasurementModels/PositionSensor2D.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MeasurementModels/PositionSensor2D.m -------------------------------------------------------------------------------- /KalmanFilters/MeasurementModels/RangeBearingSensor.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MeasurementModels/RangeBearingSensor.m -------------------------------------------------------------------------------- /KalmanFilters/MeasurementModels/VelocitySensor.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MeasurementModels/VelocitySensor.m -------------------------------------------------------------------------------- /KalmanFilters/MotionModels/BicycleModel_Continuous.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MotionModels/BicycleModel_Continuous.m -------------------------------------------------------------------------------- /KalmanFilters/MotionModels/BicycleModel_Discrete.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MotionModels/BicycleModel_Discrete.m -------------------------------------------------------------------------------- /KalmanFilters/MotionModels/ConstantAcceleration2D_Continuous.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MotionModels/ConstantAcceleration2D_Continuous.m -------------------------------------------------------------------------------- /KalmanFilters/MotionModels/ConstantAcceleration_Continuous.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MotionModels/ConstantAcceleration_Continuous.m -------------------------------------------------------------------------------- /KalmanFilters/MotionModels/ConstantVelocity2D_Continuous.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MotionModels/ConstantVelocity2D_Continuous.m -------------------------------------------------------------------------------- /KalmanFilters/MotionModels/ConstantVelocity2D_Discrete.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MotionModels/ConstantVelocity2D_Discrete.m -------------------------------------------------------------------------------- /KalmanFilters/MotionModels/ConstantVelocity_Continuous.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MotionModels/ConstantVelocity_Continuous.m -------------------------------------------------------------------------------- /KalmanFilters/MotionModels/ConstantVelocity_Discrete.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MotionModels/ConstantVelocity_Discrete.m -------------------------------------------------------------------------------- /KalmanFilters/MotionModels/ContinuousMotionModelHandler.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MotionModels/ContinuousMotionModelHandler.m -------------------------------------------------------------------------------- /KalmanFilters/MotionModels/CoordinatedTurnModel_Continuous.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MotionModels/CoordinatedTurnModel_Continuous.m -------------------------------------------------------------------------------- /KalmanFilters/MotionModels/CoordinatedTurnModel_Discrete.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MotionModels/CoordinatedTurnModel_Discrete.m -------------------------------------------------------------------------------- /KalmanFilters/MotionModels/CoordinatedTurnModel_Discrete2.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MotionModels/CoordinatedTurnModel_Discrete2.m -------------------------------------------------------------------------------- /KalmanFilters/MotionModels/CoordinatedTurnModel_Discrete_Thrun.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MotionModels/CoordinatedTurnModel_Discrete_Thrun.m -------------------------------------------------------------------------------- /KalmanFilters/MotionModels/DiscreteMotionModelHandler.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MotionModels/DiscreteMotionModelHandler.m -------------------------------------------------------------------------------- /KalmanFilters/MotionModels/TestCoordinatedTurnModel_Discrete_Thrun.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MotionModels/TestCoordinatedTurnModel_Discrete_Thrun.m -------------------------------------------------------------------------------- /KalmanFilters/MotionModels/UnicycleModel_Continuous.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/MotionModels/UnicycleModel_Continuous.m -------------------------------------------------------------------------------- /KalmanFilters/Tests/MotionModelJacobianComparison.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/Tests/MotionModelJacobianComparison.m -------------------------------------------------------------------------------- /KalmanFilters/Tests/TestEIF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/Tests/TestEIF.m -------------------------------------------------------------------------------- /KalmanFilters/Tests/TestEKF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/Tests/TestEKF.m -------------------------------------------------------------------------------- /KalmanFilters/Tests/TestKF2.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/Tests/TestKF2.m -------------------------------------------------------------------------------- /KalmanFilters/Tests/TestUKF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/Tests/TestUKF.m -------------------------------------------------------------------------------- /KalmanFilters/UKF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/UKF.m -------------------------------------------------------------------------------- /KalmanFilters/discretize_analytic.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/discretize_analytic.m -------------------------------------------------------------------------------- /KalmanFilters/discretize_bilinear.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/discretize_bilinear.m -------------------------------------------------------------------------------- /KalmanFilters/discretize_euler.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/discretize_euler.m -------------------------------------------------------------------------------- /KalmanFilters/discretize_matexp.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/discretize_matexp.m -------------------------------------------------------------------------------- /KalmanFilters/numjacobian.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/numjacobian.m -------------------------------------------------------------------------------- /KalmanFilters/numjacobian2.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/numjacobian2.m -------------------------------------------------------------------------------- /KalmanFilters/numjacobian3.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/KalmanFilters/numjacobian3.m -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/LICENSE -------------------------------------------------------------------------------- /LeastSquares/Line.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/LeastSquares/Line.m -------------------------------------------------------------------------------- /LeastSquares/Line2.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/LeastSquares/Line2.m -------------------------------------------------------------------------------- /LeastSquares/LinearLeastSquares.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/LeastSquares/LinearLeastSquares.m -------------------------------------------------------------------------------- /LeastSquares/Plane.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/LeastSquares/Plane.m -------------------------------------------------------------------------------- /LeastSquares/Plane2.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/LeastSquares/Plane2.m -------------------------------------------------------------------------------- /LeastSquares/Plane3.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/LeastSquares/Plane3.m -------------------------------------------------------------------------------- /LeastSquares/RecursiveLeastSquares.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/LeastSquares/RecursiveLeastSquares.m -------------------------------------------------------------------------------- /LeastSquares/RecursiveLeastSquares_1D.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/LeastSquares/RecursiveLeastSquares_1D.m -------------------------------------------------------------------------------- /LeastSquares/RecursiveLeastSquares_2D.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/LeastSquares/RecursiveLeastSquares_2D.m -------------------------------------------------------------------------------- /LeastSquares/RecursiveLeastSquares_KF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/LeastSquares/RecursiveLeastSquares_KF.m -------------------------------------------------------------------------------- /LeastSquares/RunningAverage.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/LeastSquares/RunningAverage.m -------------------------------------------------------------------------------- /MATLAB to Point Cloud Library/README: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MATLAB to Point Cloud Library/README -------------------------------------------------------------------------------- /MATLAB to Point Cloud Library/license.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MATLAB to Point Cloud Library/license.txt -------------------------------------------------------------------------------- /MATLAB to Point Cloud Library/loadpcd.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MATLAB to Point Cloud Library/loadpcd.m -------------------------------------------------------------------------------- /MATLAB to Point Cloud Library/lspcd.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MATLAB to Point Cloud Library/lspcd.m -------------------------------------------------------------------------------- /MATLAB to Point Cloud Library/lzfd.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MATLAB to Point Cloud Library/lzfd.m -------------------------------------------------------------------------------- /MATLAB to Point Cloud Library/pclviewer.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MATLAB to Point Cloud Library/pclviewer.m -------------------------------------------------------------------------------- /MATLAB to Point Cloud Library/resources/addons_core.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MATLAB to Point Cloud Library/resources/addons_core.xml -------------------------------------------------------------------------------- /MATLAB to Point Cloud Library/resources/matlab_path_entries.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MATLAB to Point Cloud Library/resources/matlab_path_entries.xml -------------------------------------------------------------------------------- /MATLAB to Point Cloud Library/resources/matpcl.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MATLAB to Point Cloud Library/resources/matpcl.zip -------------------------------------------------------------------------------- /MATLAB to Point Cloud Library/resources/metadata.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MATLAB to Point Cloud Library/resources/metadata.xml -------------------------------------------------------------------------------- /MATLAB to Point Cloud Library/resources/previewImage.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MATLAB to Point Cloud Library/resources/previewImage.png -------------------------------------------------------------------------------- /MATLAB to Point Cloud Library/resources/screenshot.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MATLAB to Point Cloud Library/resources/screenshot.png -------------------------------------------------------------------------------- /MATLAB to Point Cloud Library/savepcd.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MATLAB to Point Cloud Library/savepcd.m -------------------------------------------------------------------------------- /MachineLearning/HMM/DiscreteHMM/demo.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/DiscreteHMM/demo.m -------------------------------------------------------------------------------- /MachineLearning/HMM/DiscreteHMM/discreteRnd.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/DiscreteHMM/discreteRnd.m -------------------------------------------------------------------------------- /MachineLearning/HMM/DiscreteHMM/hmmEm.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/DiscreteHMM/hmmEm.m -------------------------------------------------------------------------------- /MachineLearning/HMM/DiscreteHMM/hmmFilter.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/DiscreteHMM/hmmFilter.m -------------------------------------------------------------------------------- /MachineLearning/HMM/DiscreteHMM/hmmFilter_.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/DiscreteHMM/hmmFilter_.m -------------------------------------------------------------------------------- /MachineLearning/HMM/DiscreteHMM/hmmRnd.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/DiscreteHMM/hmmRnd.m -------------------------------------------------------------------------------- /MachineLearning/HMM/DiscreteHMM/hmmSmoother.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/DiscreteHMM/hmmSmoother.m -------------------------------------------------------------------------------- /MachineLearning/HMM/DiscreteHMM/hmmSmoother_.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/DiscreteHMM/hmmSmoother_.m -------------------------------------------------------------------------------- /MachineLearning/HMM/DiscreteHMM/hmmViterbi.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/DiscreteHMM/hmmViterbi.m -------------------------------------------------------------------------------- /MachineLearning/HMM/DiscreteHMM/hmmViterbi_.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/DiscreteHMM/hmmViterbi_.m -------------------------------------------------------------------------------- /MachineLearning/HMM/DiscreteHMM/license.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/DiscreteHMM/license.txt -------------------------------------------------------------------------------- /MachineLearning/HMM/DiscreteHMM/normalize.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/DiscreteHMM/normalize.m -------------------------------------------------------------------------------- /MachineLearning/HMM/GaussianHMM/em_ghmm.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/GaussianHMM/em_ghmm.c -------------------------------------------------------------------------------- /MachineLearning/HMM/GaussianHMM/forward_backward.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/GaussianHMM/forward_backward.c -------------------------------------------------------------------------------- /MachineLearning/HMM/GaussianHMM/license.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/GaussianHMM/license.txt -------------------------------------------------------------------------------- /MachineLearning/HMM/GaussianHMM/likelihood_mvgm.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/GaussianHMM/likelihood_mvgm.c -------------------------------------------------------------------------------- /MachineLearning/HMM/GaussianHMM/mexme_em_ghmm.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/GaussianHMM/mexme_em_ghmm.m -------------------------------------------------------------------------------- /MachineLearning/HMM/GaussianHMM/ndellipse.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/GaussianHMM/ndellipse.c -------------------------------------------------------------------------------- /MachineLearning/HMM/GaussianHMM/sample_ghmm.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/GaussianHMM/sample_ghmm.c -------------------------------------------------------------------------------- /MachineLearning/HMM/GaussianHMM/test_em_ghmm.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/MachineLearning/HMM/GaussianHMM/test_em_ghmm.m -------------------------------------------------------------------------------- /Madgwick/@MadgwickAHRS/MadgwickAHRS.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Madgwick/@MadgwickAHRS/MadgwickAHRS.m -------------------------------------------------------------------------------- /Madgwick/@MahonyAHRS/MahonyAHRS.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Madgwick/@MahonyAHRS/MahonyAHRS.m -------------------------------------------------------------------------------- /Madgwick/ExampleScript.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Madgwick/ExampleScript.m -------------------------------------------------------------------------------- /Madgwick/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Madgwick/LICENSE -------------------------------------------------------------------------------- /Madgwick/quaternion_library/TestScript.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Madgwick/quaternion_library/TestScript.m -------------------------------------------------------------------------------- /Madgwick/quaternion_library/axisAngle2quatern.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Madgwick/quaternion_library/axisAngle2quatern.m -------------------------------------------------------------------------------- /Madgwick/quaternion_library/axisAngle2rotMat.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Madgwick/quaternion_library/axisAngle2rotMat.m -------------------------------------------------------------------------------- /Madgwick/quaternion_library/euler2rotMat.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Madgwick/quaternion_library/euler2rotMat.m -------------------------------------------------------------------------------- /Madgwick/quaternion_library/quatern2euler.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Madgwick/quaternion_library/quatern2euler.m -------------------------------------------------------------------------------- /Madgwick/quaternion_library/quatern2rotMat.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Madgwick/quaternion_library/quatern2rotMat.m -------------------------------------------------------------------------------- /Madgwick/quaternion_library/quaternConj.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Madgwick/quaternion_library/quaternConj.m -------------------------------------------------------------------------------- /Madgwick/quaternion_library/quaternProd.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Madgwick/quaternion_library/quaternProd.m -------------------------------------------------------------------------------- /Madgwick/quaternion_library/rotMat2euler.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Madgwick/quaternion_library/rotMat2euler.m -------------------------------------------------------------------------------- /Madgwick/quaternion_library/rotMat2quatern.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Madgwick/quaternion_library/rotMat2quatern.m -------------------------------------------------------------------------------- /Mapping/AMCL.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Mapping/AMCL.m -------------------------------------------------------------------------------- /Mapping/AMCL2.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Mapping/AMCL2.m -------------------------------------------------------------------------------- /Mapping/BeamRangeSensor.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Mapping/BeamRangeSensor.m -------------------------------------------------------------------------------- /Mapping/CarSim.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Mapping/CarSim.m -------------------------------------------------------------------------------- /Mapping/OccupancyGrid/OccupancyGrid.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Mapping/OccupancyGrid/OccupancyGrid.m -------------------------------------------------------------------------------- /Mapping/ScanICP.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Mapping/ScanICP.m -------------------------------------------------------------------------------- /Mapping/TestAMCL.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Mapping/TestAMCL.m -------------------------------------------------------------------------------- /Mapping/TestBeamRangeSensor.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Mapping/TestBeamRangeSensor.m -------------------------------------------------------------------------------- /Mapping/TestOccupancyMapping.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Mapping/TestOccupancyMapping.m -------------------------------------------------------------------------------- /Mapping/TestScanMatching.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Mapping/TestScanMatching.m -------------------------------------------------------------------------------- /Mapping/example.bmp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Mapping/example.bmp -------------------------------------------------------------------------------- /Mapping/straight.bmp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Mapping/straight.bmp -------------------------------------------------------------------------------- /Mapping/straight2.bmp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Mapping/straight2.bmp -------------------------------------------------------------------------------- /Mapping/straight3.bmp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Mapping/straight3.bmp -------------------------------------------------------------------------------- /Optimization/GraphOptimization/To Do.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/GraphOptimization/To Do.txt -------------------------------------------------------------------------------- /Optimization/LevenbergMarquardt/ExampleWithAndWithoutJacobian.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/LevenbergMarquardt/ExampleWithAndWithoutJacobian.m -------------------------------------------------------------------------------- /Optimization/LevenbergMarquardt/Example_nested_contraction.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/LevenbergMarquardt/Example_nested_contraction.m -------------------------------------------------------------------------------- /Optimization/LevenbergMarquardt/LMFnlsq/LMFnlsq.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/LevenbergMarquardt/LMFnlsq/LMFnlsq.m -------------------------------------------------------------------------------- /Optimization/LevenbergMarquardt/LMFnlsq/LMFnlsqtest.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/LevenbergMarquardt/LMFnlsq/LMFnlsqtest.m -------------------------------------------------------------------------------- /Optimization/LevenbergMarquardt/LMFnlsq/LMFnlsqtest.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/LevenbergMarquardt/LMFnlsq/LMFnlsqtest.pdf -------------------------------------------------------------------------------- /Optimization/LevenbergMarquardt/LMFnlsq/license.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/LevenbergMarquardt/LMFnlsq/license.txt -------------------------------------------------------------------------------- /Optimization/LevenbergMarquardt/LMFnlsq/res.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/LevenbergMarquardt/LMFnlsq/res.m -------------------------------------------------------------------------------- /Optimization/LevenbergMarquardt/LMFsolve/LMFsolve.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/LevenbergMarquardt/LMFsolve/LMFsolve.m -------------------------------------------------------------------------------- /Optimization/LevenbergMarquardt/LMFsolve/LMFsolveOLD.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/LevenbergMarquardt/LMFsolve/LMFsolveOLD.m -------------------------------------------------------------------------------- /Optimization/LevenbergMarquardt/LMFsolve/LMFsolvetest.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/LevenbergMarquardt/LMFsolve/LMFsolvetest.m -------------------------------------------------------------------------------- /Optimization/LevenbergMarquardt/LMFsolve/license.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/LevenbergMarquardt/LMFsolve/license.txt -------------------------------------------------------------------------------- /Optimization/LevenbergMarquardt/LMFsolve/rosen.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/LevenbergMarquardt/LMFsolve/rosen.m -------------------------------------------------------------------------------- /Optimization/LevenbergMarquardt/LMsimple/lm.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/LevenbergMarquardt/LMsimple/lm.m -------------------------------------------------------------------------------- /Optimization/LevenbergMarquardt/LMsimple/lm_examp.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/LevenbergMarquardt/LMsimple/lm_examp.m -------------------------------------------------------------------------------- /Optimization/LevenbergMarquardt/LMsimple/lm_func.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/LevenbergMarquardt/LMsimple/lm_func.m -------------------------------------------------------------------------------- /Optimization/LevenbergMarquardt/LMsimple/lm_plots.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/LevenbergMarquardt/LMsimple/lm_plots.m -------------------------------------------------------------------------------- /Optimization/LevenbergMarquardt/LevenbergMarquardt.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/LevenbergMarquardt/LevenbergMarquardt.m -------------------------------------------------------------------------------- /Optimization/LevenbergMarquardt/license.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/LevenbergMarquardt/license.txt -------------------------------------------------------------------------------- /Optimization/LevenbergMarquardt/nested_contraction_obj.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/LevenbergMarquardt/nested_contraction_obj.m -------------------------------------------------------------------------------- /Optimization/NonlinearOptimizers.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/NonlinearOptimizers.m -------------------------------------------------------------------------------- /Optimization/TestNonlinearOptimizers.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/TestNonlinearOptimizers.m -------------------------------------------------------------------------------- /Optimization/jacobianext.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/jacobianext.m -------------------------------------------------------------------------------- /Optimization/jacobianlim.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/jacobianlim.m -------------------------------------------------------------------------------- /Optimization/jacobiansimple.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/jacobiansimple.m -------------------------------------------------------------------------------- /Optimization/license.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/license.txt -------------------------------------------------------------------------------- /Optimization/numjacobian.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Optimization/numjacobian.m -------------------------------------------------------------------------------- /PCD/MATLAB to Point Cloud Library - File Exchange - MATLAB Central.desktop: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/PCD/MATLAB to Point Cloud Library - File Exchange - MATLAB Central.desktop -------------------------------------------------------------------------------- /PCD/boxFilter.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/PCD/boxFilter.m -------------------------------------------------------------------------------- /PCD/combinePCD.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/PCD/combinePCD.m -------------------------------------------------------------------------------- /PCD/enablePCDtooltip.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/PCD/enablePCDtooltip.m -------------------------------------------------------------------------------- /PCD/extractPCD.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/PCD/extractPCD.m -------------------------------------------------------------------------------- /PCD/getBoundingBox.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/PCD/getBoundingBox.m -------------------------------------------------------------------------------- /PCD/loadPCD.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/PCD/loadPCD.m -------------------------------------------------------------------------------- /PCD/loadpcd_auto.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/PCD/loadpcd_auto.m -------------------------------------------------------------------------------- /PCD/loadpcd_raw.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/PCD/loadpcd_raw.m -------------------------------------------------------------------------------- /PCD/pcdHeader.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/PCD/pcdHeader.m -------------------------------------------------------------------------------- /PCD/plotPCD.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/PCD/plotPCD.m -------------------------------------------------------------------------------- /PCD/plotTransform.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/PCD/plotTransform.m -------------------------------------------------------------------------------- /PCD/plotValues.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/PCD/plotValues.m -------------------------------------------------------------------------------- /PCD/removeFromPCD.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/PCD/removeFromPCD.m -------------------------------------------------------------------------------- /PCD/rotatePCD.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/PCD/rotatePCD.m -------------------------------------------------------------------------------- /PCD/savepcd.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/PCD/savepcd.m -------------------------------------------------------------------------------- /PCD/savepcdOld.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/PCD/savepcdOld.m -------------------------------------------------------------------------------- /PCD/sortPCD.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/PCD/sortPCD.m -------------------------------------------------------------------------------- /PCD/transformPCD.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/PCD/transformPCD.m -------------------------------------------------------------------------------- /ParticleFilters/BootstrapFilter/AdaptiveParticleFilter.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ParticleFilters/BootstrapFilter/AdaptiveParticleFilter.m -------------------------------------------------------------------------------- /ParticleFilters/BootstrapFilter/BootstrapFilter.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ParticleFilters/BootstrapFilter/BootstrapFilter.m -------------------------------------------------------------------------------- /ParticleFilters/BootstrapFilter/BootstrapSISFilter.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ParticleFilters/BootstrapFilter/BootstrapSISFilter.m -------------------------------------------------------------------------------- /ParticleFilters/BootstrapFilter/ImportanceSampling_WeightedSamples.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ParticleFilters/BootstrapFilter/ImportanceSampling_WeightedSamples.m -------------------------------------------------------------------------------- /ParticleFilters/BootstrapFilter/ImprovedSIRFilter.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ParticleFilters/BootstrapFilter/ImprovedSIRFilter.m -------------------------------------------------------------------------------- /ParticleFilters/BootstrapFilter/SIRFilter.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ParticleFilters/BootstrapFilter/SIRFilter.m -------------------------------------------------------------------------------- /ParticleFilters/BootstrapFilter/TestFilter.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ParticleFilters/BootstrapFilter/TestFilter.m -------------------------------------------------------------------------------- /ParticleFilters/BootstrapFilter/TestImportanceSampling.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ParticleFilters/BootstrapFilter/TestImportanceSampling.m -------------------------------------------------------------------------------- /ParticleFilters/MPF/experiment.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ParticleFilters/MPF/experiment.m -------------------------------------------------------------------------------- /ParticleFilters/MPF/mpf.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ParticleFilters/MPF/mpf.m -------------------------------------------------------------------------------- /ParticleFilters/MPF/pf.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ParticleFilters/MPF/pf.m -------------------------------------------------------------------------------- /ParticleFilters/MPF/sysresample.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ParticleFilters/MPF/sysresample.m -------------------------------------------------------------------------------- /ParticleFilters/RaoBlackwellizedPF/RaoBlackwellizedPF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ParticleFilters/RaoBlackwellizedPF/RaoBlackwellizedPF.m -------------------------------------------------------------------------------- /ParticleFilters/RaoBlackwellizedPF/RaoBlackwellizedParticle.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ParticleFilters/RaoBlackwellizedPF/RaoBlackwellizedParticle.m -------------------------------------------------------------------------------- /ParticleFilters/RaoBlackwellizedPF/TestRaoBlackwellizedPF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ParticleFilters/RaoBlackwellizedPF/TestRaoBlackwellizedPF.m -------------------------------------------------------------------------------- /Planning/GraphAlgorithms/DijkstraAstarTest.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Planning/GraphAlgorithms/DijkstraAstarTest.m -------------------------------------------------------------------------------- /Planning/GraphAlgorithms/NonHolonomicPlanning.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Planning/GraphAlgorithms/NonHolonomicPlanning.m -------------------------------------------------------------------------------- /Planning/GraphAlgorithms/PriorityQueue/PriorityQueue.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Planning/GraphAlgorithms/PriorityQueue/PriorityQueue.m -------------------------------------------------------------------------------- /Planning/GraphAlgorithms/PriorityQueue/license.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Planning/GraphAlgorithms/PriorityQueue/license.txt -------------------------------------------------------------------------------- /Planning/GraphAlgorithms/PriorityQueue2.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Planning/GraphAlgorithms/PriorityQueue2.m -------------------------------------------------------------------------------- /Planning/GraphAlgorithms/Robot.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Planning/GraphAlgorithms/Robot.m -------------------------------------------------------------------------------- /Planning/GraphAlgorithms/track.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Planning/GraphAlgorithms/track.png -------------------------------------------------------------------------------- /Quaternion/ExtractHeading.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/ExtractHeading.m -------------------------------------------------------------------------------- /Quaternion/Gamma.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/Gamma.m -------------------------------------------------------------------------------- /Quaternion/HeadingErrorWrapping.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/HeadingErrorWrapping.m -------------------------------------------------------------------------------- /Quaternion/HeadingIndependentReference.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/HeadingIndependentReference.m -------------------------------------------------------------------------------- /Quaternion/HeadingQuaternion.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/HeadingQuaternion.m -------------------------------------------------------------------------------- /Quaternion/Phi.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/Phi.m -------------------------------------------------------------------------------- /Quaternion/Quaternion2ZYXEulerAngles.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/Quaternion2ZYXEulerAngles.m -------------------------------------------------------------------------------- /Quaternion/QuaternionError.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/QuaternionError.m -------------------------------------------------------------------------------- /Quaternion/QuaternionNoiseCovarianceMatrix.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/QuaternionNoiseCovarianceMatrix.m -------------------------------------------------------------------------------- /Quaternion/QuaternionPropagationWithBias.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/QuaternionPropagationWithBias.m -------------------------------------------------------------------------------- /Quaternion/QuaternionTransitionMatrix.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/QuaternionTransitionMatrix.m -------------------------------------------------------------------------------- /Quaternion/ZYXEulerAngles2Quaternion.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/ZYXEulerAngles2Quaternion.m -------------------------------------------------------------------------------- /Quaternion/axang2quat.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/axang2quat.m -------------------------------------------------------------------------------- /Quaternion/eul2quat.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/eul2quat.m -------------------------------------------------------------------------------- /Quaternion/matrix2quaternion.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/matrix2quaternion.m -------------------------------------------------------------------------------- /Quaternion/omega_b2qdot.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/omega_b2qdot.m -------------------------------------------------------------------------------- /Quaternion/q2tr.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/q2tr.m -------------------------------------------------------------------------------- /Quaternion/qdevec.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/qdevec.m -------------------------------------------------------------------------------- /Quaternion/qdot2omega_b.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/qdot2omega_b.m -------------------------------------------------------------------------------- /Quaternion/quat2angle.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/quat2angle.m -------------------------------------------------------------------------------- /Quaternion/quat2axang.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/quat2axang.m -------------------------------------------------------------------------------- /Quaternion/quat2eul.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/quat2eul.m -------------------------------------------------------------------------------- /Quaternion/quat2rotm.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/quat2rotm.m -------------------------------------------------------------------------------- /Quaternion/quatconj.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/quatconj.m -------------------------------------------------------------------------------- /Quaternion/quatexp.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/quatexp.m -------------------------------------------------------------------------------- /Quaternion/quatinv.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/quatinv.m -------------------------------------------------------------------------------- /Quaternion/quatlogn.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/quatlogn.m -------------------------------------------------------------------------------- /Quaternion/quatmod.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/quatmod.m -------------------------------------------------------------------------------- /Quaternion/quatmul.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/quatmul.m -------------------------------------------------------------------------------- /Quaternion/quatmultiply.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/quatmultiply.m -------------------------------------------------------------------------------- /Quaternion/quatnorm.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/quatnorm.m -------------------------------------------------------------------------------- /Quaternion/quatnormalize.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/quatnormalize.m -------------------------------------------------------------------------------- /Quaternion/quatpow.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/quatpow.m -------------------------------------------------------------------------------- /Quaternion/quatslerp.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/quatslerp.m -------------------------------------------------------------------------------- /Quaternion/quatslerp2.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/quatslerp2.m -------------------------------------------------------------------------------- /Quaternion/qvec.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/qvec.m -------------------------------------------------------------------------------- /Quaternion/rotm2quat.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/rotm2quat.m -------------------------------------------------------------------------------- /Quaternion/rvec2quat.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/rvec2quat.m -------------------------------------------------------------------------------- /Quaternion/tr2q.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/tr2q.m -------------------------------------------------------------------------------- /Quaternion/unwrapangle.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/unwrapangle.m -------------------------------------------------------------------------------- /Quaternion/unwrapstep.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/unwrapstep.m -------------------------------------------------------------------------------- /Quaternion/wrapTo2Pi.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/wrapTo2Pi.m -------------------------------------------------------------------------------- /Quaternion/wrapToPi.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Quaternion/wrapToPi.m -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/README.md -------------------------------------------------------------------------------- /ReplaceStringInFile.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ReplaceStringInFile.m -------------------------------------------------------------------------------- /RotationMatrix/SpinCalc.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/RotationMatrix/SpinCalc.m -------------------------------------------------------------------------------- /RotationMatrix/eul2rotm.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/RotationMatrix/eul2rotm.m -------------------------------------------------------------------------------- /RotationMatrix/rot2.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/RotationMatrix/rot2.m -------------------------------------------------------------------------------- /RotationMatrix/rotationBetweenVectors.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/RotationMatrix/rotationBetweenVectors.m -------------------------------------------------------------------------------- /RotationMatrix/rotm2eul.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/RotationMatrix/rotm2eul.m -------------------------------------------------------------------------------- /RotationMatrix/rotm2heading.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/RotationMatrix/rotm2heading.m -------------------------------------------------------------------------------- /RotationMatrix/rotm2tf.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/RotationMatrix/rotm2tf.m -------------------------------------------------------------------------------- /RotationMatrix/rotx.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/RotationMatrix/rotx.m -------------------------------------------------------------------------------- /RotationMatrix/roty.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/RotationMatrix/roty.m -------------------------------------------------------------------------------- /RotationMatrix/rotz.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/RotationMatrix/rotz.m -------------------------------------------------------------------------------- /RotationMatrix/tf2heading.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/RotationMatrix/tf2heading.m -------------------------------------------------------------------------------- /RotationMatrix/tf2rotm.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/RotationMatrix/tf2rotm.m -------------------------------------------------------------------------------- /RotationMatrix/trotx.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/RotationMatrix/trotx.m -------------------------------------------------------------------------------- /RotationMatrix/troty.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/RotationMatrix/troty.m -------------------------------------------------------------------------------- /RotationMatrix/trotz.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/RotationMatrix/trotz.m -------------------------------------------------------------------------------- /ScanMatching/GitHub_szandara-2DScanMatching.url: -------------------------------------------------------------------------------- 1 | [InternetShortcut] 2 | URL=https://github.com/szandara/2DScanMatching_SLAM 3 | -------------------------------------------------------------------------------- /ScanMatching/ICP2D.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ScanMatching/ICP2D.m -------------------------------------------------------------------------------- /ScanMatching/See also ICP folder.txt: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /ScanMatching/Test2D_ICP.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ScanMatching/Test2D_ICP.m -------------------------------------------------------------------------------- /ScanMatching/Test2DscanMatching.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ScanMatching/Test2DscanMatching.m -------------------------------------------------------------------------------- /ScanMatching/registerCensi.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ScanMatching/registerCensi.m -------------------------------------------------------------------------------- /ScanMatching/registerLSQ.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ScanMatching/registerLSQ.m -------------------------------------------------------------------------------- /ScanMatching/registerSVD.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ScanMatching/registerSVD.m -------------------------------------------------------------------------------- /Statistics/betacdf.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/betacdf.m -------------------------------------------------------------------------------- /Statistics/betainv.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/betainv.m -------------------------------------------------------------------------------- /Statistics/betapdf.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/betapdf.m -------------------------------------------------------------------------------- /Statistics/betarnd.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/betarnd.m -------------------------------------------------------------------------------- /Statistics/chi2cdf.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/chi2cdf.m -------------------------------------------------------------------------------- /Statistics/chi2inv.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/chi2inv.m -------------------------------------------------------------------------------- /Statistics/exprnd.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/exprnd.m -------------------------------------------------------------------------------- /Statistics/gamcdf.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/gamcdf.m -------------------------------------------------------------------------------- /Statistics/gaminv.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/gaminv.m -------------------------------------------------------------------------------- /Statistics/gampdf.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/gampdf.m -------------------------------------------------------------------------------- /Statistics/gamrnd.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/gamrnd.m -------------------------------------------------------------------------------- /Statistics/normcdf.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/normcdf.m -------------------------------------------------------------------------------- /Statistics/normcdf2.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/normcdf2.m -------------------------------------------------------------------------------- /Statistics/norminv.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/norminv.m -------------------------------------------------------------------------------- /Statistics/normpdf.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/normpdf.m -------------------------------------------------------------------------------- /Statistics/normrnd.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/normrnd.m -------------------------------------------------------------------------------- /Statistics/stdnormal_cdf.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/stdnormal_cdf.m -------------------------------------------------------------------------------- /Statistics/stdnormal_inv.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/stdnormal_inv.m -------------------------------------------------------------------------------- /Statistics/stdnormal_pdf.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/stdnormal_pdf.m -------------------------------------------------------------------------------- /Statistics/tcdf.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/tcdf.m -------------------------------------------------------------------------------- /Statistics/tinv.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/tinv.m -------------------------------------------------------------------------------- /Statistics/tpdf.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/tpdf.m -------------------------------------------------------------------------------- /Statistics/trnd.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/trnd.m -------------------------------------------------------------------------------- /Statistics/tstat.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/tstat.m -------------------------------------------------------------------------------- /Statistics/wblcdf.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/wblcdf.m -------------------------------------------------------------------------------- /Statistics/wblinv.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/wblinv.m -------------------------------------------------------------------------------- /Statistics/wblrnd.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Statistics/wblrnd.m -------------------------------------------------------------------------------- /TimeSeries/Downsample.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/TimeSeries/Downsample.m -------------------------------------------------------------------------------- /TimeSeries/Extract.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/TimeSeries/Extract.m -------------------------------------------------------------------------------- /TimeSeries/Trim.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/TimeSeries/Trim.m -------------------------------------------------------------------------------- /TimeSeries/findMatchingIndex.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/TimeSeries/findMatchingIndex.m -------------------------------------------------------------------------------- /Tracking/SOT/GroundtruthGenerator.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/Tracking/SOT/GroundtruthGenerator.m -------------------------------------------------------------------------------- /absor.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/absor.m -------------------------------------------------------------------------------- /atan2_approximation.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/atan2_approximation.m -------------------------------------------------------------------------------- /bestblk.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/bestblk.m -------------------------------------------------------------------------------- /bin2float.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/bin2float.m -------------------------------------------------------------------------------- /circle.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/circle.m -------------------------------------------------------------------------------- /colorPlot2D.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/colorPlot2D.m -------------------------------------------------------------------------------- /colorPlot3D.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/colorPlot3D.m -------------------------------------------------------------------------------- /columns.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/columns.m -------------------------------------------------------------------------------- /corrcoef/corrcoef.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/corrcoef/corrcoef.m -------------------------------------------------------------------------------- /corrcoef/flag_implicit_skip_nan.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/corrcoef/flag_implicit_skip_nan.m -------------------------------------------------------------------------------- /corrcoef/sumskipnan.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/corrcoef/sumskipnan.m -------------------------------------------------------------------------------- /corrcoef/tcdf.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/corrcoef/tcdf.m -------------------------------------------------------------------------------- /csvwrite_with_headers.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/csvwrite_with_headers.m -------------------------------------------------------------------------------- /fitmethis.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/fitmethis.m -------------------------------------------------------------------------------- /float2bin.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/float2bin.m -------------------------------------------------------------------------------- /getUnixTimestampsFromFilenames.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/getUnixTimestampsFromFilenames.m -------------------------------------------------------------------------------- /getdatesortedfiles.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/getdatesortedfiles.m -------------------------------------------------------------------------------- /getlatestfile.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/getlatestfile.m -------------------------------------------------------------------------------- /hline.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/hline.m -------------------------------------------------------------------------------- /immarker.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/immarker.m -------------------------------------------------------------------------------- /imresize.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/imresize.m -------------------------------------------------------------------------------- /isfile2.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/isfile2.m -------------------------------------------------------------------------------- /isgray.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/isgray.m -------------------------------------------------------------------------------- /isint.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/isint.m -------------------------------------------------------------------------------- /isnum.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/isnum.m -------------------------------------------------------------------------------- /isrow2.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/isrow2.m -------------------------------------------------------------------------------- /issquare.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/issquare.m -------------------------------------------------------------------------------- /jetColor.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/jetColor.m -------------------------------------------------------------------------------- /jetColorLUT.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/jetColorLUT.m -------------------------------------------------------------------------------- /mod2pi.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/mod2pi.m -------------------------------------------------------------------------------- /nanmean.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/nanmean.m -------------------------------------------------------------------------------- /nearestneighbour/demo/html/nndemo.html: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/nearestneighbour/demo/html/nndemo.html -------------------------------------------------------------------------------- /nearestneighbour/demo/html/nndemo.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/nearestneighbour/demo/html/nndemo.png -------------------------------------------------------------------------------- /nearestneighbour/demo/html/nndemo_01.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/nearestneighbour/demo/html/nndemo_01.png -------------------------------------------------------------------------------- /nearestneighbour/demo/html/nndemo_02.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/nearestneighbour/demo/html/nndemo_02.png -------------------------------------------------------------------------------- /nearestneighbour/demo/html/nndemo_03.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/nearestneighbour/demo/html/nndemo_03.png -------------------------------------------------------------------------------- /nearestneighbour/demo/html/nndemo_04.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/nearestneighbour/demo/html/nndemo_04.png -------------------------------------------------------------------------------- /nearestneighbour/demo/nndemo.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/nearestneighbour/demo/nndemo.m -------------------------------------------------------------------------------- /nearestneighbour/demo/nndemo.mlx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/nearestneighbour/demo/nndemo.mlx -------------------------------------------------------------------------------- /nearestneighbour/demo/timingtest.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/nearestneighbour/demo/timingtest.m -------------------------------------------------------------------------------- /nearestneighbour/license.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/nearestneighbour/license.txt -------------------------------------------------------------------------------- /nearestneighbour/nearestneighbour.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/nearestneighbour/nearestneighbour.m -------------------------------------------------------------------------------- /ordeig2.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/ordeig2.m -------------------------------------------------------------------------------- /plotfitdist.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/plotfitdist.m -------------------------------------------------------------------------------- /principalValue.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/principalValue.m -------------------------------------------------------------------------------- /rows.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/rows.m -------------------------------------------------------------------------------- /saveImage.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/saveImage.m -------------------------------------------------------------------------------- /smooth.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/smooth.m -------------------------------------------------------------------------------- /startup.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/startup.m -------------------------------------------------------------------------------- /stats-matlab/common_size.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/stats-matlab/common_size.m -------------------------------------------------------------------------------- /stats-matlab/corr.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/stats-matlab/corr.m -------------------------------------------------------------------------------- /stats-matlab/quantile.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/stats-matlab/quantile.m -------------------------------------------------------------------------------- /strsplit/private/ischarint.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/strsplit/private/ischarint.m -------------------------------------------------------------------------------- /strsplit/private/ischarnum.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/strsplit/private/ischarnum.m -------------------------------------------------------------------------------- /strsplit/strsplit.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/strsplit/strsplit.m -------------------------------------------------------------------------------- /struct2array.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/struct2array.m -------------------------------------------------------------------------------- /timestampFromFilename.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/timestampFromFilename.m -------------------------------------------------------------------------------- /utilities/axang2quat.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/axang2quat.m -------------------------------------------------------------------------------- /utilities/axang2rotm.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/axang2rotm.m -------------------------------------------------------------------------------- /utilities/baseVel2params.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/baseVel2params.m -------------------------------------------------------------------------------- /utilities/deul.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/deul.m -------------------------------------------------------------------------------- /utilities/deul2angVel.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/deul2angVel.m -------------------------------------------------------------------------------- /utilities/dquat.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/dquat.m -------------------------------------------------------------------------------- /utilities/eul2angRateTF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/eul2angRateTF.m -------------------------------------------------------------------------------- /utilities/eul2angVelTF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/eul2angVelTF.m -------------------------------------------------------------------------------- /utilities/eul2quat.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/eul2quat.m -------------------------------------------------------------------------------- /utilities/eul2rotm.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/eul2rotm.m -------------------------------------------------------------------------------- /utilities/fastForwardDynamics.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/fastForwardDynamics.m -------------------------------------------------------------------------------- /utilities/fastGetStateParams.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/fastGetStateParams.m -------------------------------------------------------------------------------- /utilities/fastIntForwardDynamics.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/fastIntForwardDynamics.m -------------------------------------------------------------------------------- /utilities/fileExist.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/fileExist.m -------------------------------------------------------------------------------- /utilities/frame2posEul.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/frame2posEul.m -------------------------------------------------------------------------------- /utilities/frame2posRotm.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/frame2posRotm.m -------------------------------------------------------------------------------- /utilities/frame2tform.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/frame2tform.m -------------------------------------------------------------------------------- /utilities/generalizedBaseAcc.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/generalizedBaseAcc.m -------------------------------------------------------------------------------- /utilities/getJointAnnotationICub.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/getJointAnnotationICub.m -------------------------------------------------------------------------------- /utilities/getJointNamesFromURDF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/getJointNamesFromURDF.m -------------------------------------------------------------------------------- /utilities/getSimConfigFromURDF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/getSimConfigFromURDF.m -------------------------------------------------------------------------------- /utilities/initJointsFromNameList.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/initJointsFromNameList.m -------------------------------------------------------------------------------- /utilities/isHomog.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/isHomog.m -------------------------------------------------------------------------------- /utilities/isNormalized.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/isNormalized.m -------------------------------------------------------------------------------- /utilities/isRadians.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/isRadians.m -------------------------------------------------------------------------------- /utilities/isStateEmpty.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/isStateEmpty.m -------------------------------------------------------------------------------- /utilities/params2rotoTrans.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/params2rotoTrans.m -------------------------------------------------------------------------------- /utilities/params2stateVec.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/params2stateVec.m -------------------------------------------------------------------------------- /utilities/plotquat.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/plotquat.m -------------------------------------------------------------------------------- /utilities/posRotm2tform.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/posRotm2tform.m -------------------------------------------------------------------------------- /utilities/quat2axang.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/quat2axang.m -------------------------------------------------------------------------------- /utilities/quat2eul.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/quat2eul.m -------------------------------------------------------------------------------- /utilities/quat2rotm.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/quat2rotm.m -------------------------------------------------------------------------------- /utilities/quat2tform.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/quat2tform.m -------------------------------------------------------------------------------- /utilities/quatconj.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/quatconj.m -------------------------------------------------------------------------------- /utilities/quatdiv.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/quatdiv.m -------------------------------------------------------------------------------- /utilities/quatinv.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/quatinv.m -------------------------------------------------------------------------------- /utilities/quatmagnitude.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/quatmagnitude.m -------------------------------------------------------------------------------- /utilities/quatmult.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/quatmult.m -------------------------------------------------------------------------------- /utilities/quatnorm.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/quatnorm.m -------------------------------------------------------------------------------- /utilities/quatnormalize.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/quatnormalize.m -------------------------------------------------------------------------------- /utilities/quatslerp.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/quatslerp.m -------------------------------------------------------------------------------- /utilities/rotm2axang.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/rotm2axang.m -------------------------------------------------------------------------------- /utilities/rotm2eul.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/rotm2eul.m -------------------------------------------------------------------------------- /utilities/rotm2eulAngVelTF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/rotm2eulAngVelTF.m -------------------------------------------------------------------------------- /utilities/rotm2quat.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/rotm2quat.m -------------------------------------------------------------------------------- /utilities/rotx.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/rotx.m -------------------------------------------------------------------------------- /utilities/roty.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/roty.m -------------------------------------------------------------------------------- /utilities/rotz.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/rotz.m -------------------------------------------------------------------------------- /utilities/skewm.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/skewm.m -------------------------------------------------------------------------------- /utilities/skewm2vec.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/skewm2vec.m -------------------------------------------------------------------------------- /utilities/tform2angRateTF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/tform2angRateTF.m -------------------------------------------------------------------------------- /utilities/tform2angVelTF.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/tform2angVelTF.m -------------------------------------------------------------------------------- /utilities/tform2axang.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/tform2axang.m -------------------------------------------------------------------------------- /utilities/tform2eul.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/tform2eul.m -------------------------------------------------------------------------------- /utilities/tform2frame.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/tform2frame.m -------------------------------------------------------------------------------- /utilities/tform2posRotm.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/tform2posRotm.m -------------------------------------------------------------------------------- /utilities/tform2quat.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/utilities/tform2quat.m -------------------------------------------------------------------------------- /vec.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/vec.m -------------------------------------------------------------------------------- /vline.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mindThomas/MATLAB-tools/HEAD/vline.m --------------------------------------------------------------------------------