Fixed some Doxygen problems with global replace

release/4.3a0
Frank Dellaert 2011-10-14 03:23:14 +00:00
parent 2294924ee9
commit 56d1d6ae34
82 changed files with 301 additions and 341 deletions

View File

@ -9,13 +9,13 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* Pose2SLAMExample_easy.cpp * @file Pose2SLAMExample_easy.cpp
* *
* A 2D Pose SLAM example using the predefined typedefs in gtsam/slam/pose2SLAM.h * A 2D Pose SLAM example using the predefined typedefs in gtsam/slam/pose2SLAM.h
* *
* Created on: Oct 21, 2010 * @date Oct 21, 2010
* Author: ydjian * @author ydjian
*/ */
#include <cmath> #include <cmath>

View File

@ -9,12 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* SimpleRotation.cpp * @file SimpleRotation.cpp
* * @brief This is a super-simple example of optimizing a single rotation according to a single prior
* This is a super-simple example of optimizing a single rotation according to a single prior * @date Jul 1, 2010
*
* Created on: Jul 1, 2010
* @author Frank Dellaert * @author Frank Dellaert
* @author Alex Cunningham * @author Alex Cunningham
*/ */

View File

@ -9,14 +9,14 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* easyPoint2KalmanFilter.cpp * @file easyPoint2KalmanFilter.cpp
* *
* simple linear Kalman filter on a moving 2D point, but done using factor graphs * simple linear Kalman filter on a moving 2D point, but done using factor graphs
* This example uses the templated ExtendedKalmanFilter class to perform the same * This example uses the templated ExtendedKalmanFilter class to perform the same
* operations as in elaboratePoint2KalmanFilter * operations as in elaboratePoint2KalmanFilter
* *
* Created on: Aug 19, 2011 * @date Aug 19, 2011
* @author Frank Dellaert * @author Frank Dellaert
* @author Stephen Williams * @author Stephen Williams
*/ */

View File

@ -9,13 +9,13 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* elaboratePoint2KalmanFilter.cpp * @file elaboratePoint2KalmanFilter.cpp
* *
* simple linear Kalman filter on a moving 2D point, but done using factor graphs * simple linear Kalman filter on a moving 2D point, but done using factor graphs
* This example manually creates all of the needed data structures * This example manually creates all of the needed data structures
* *
* Created on: Aug 19, 2011 * @date Aug 19, 2011
* @author Frank Dellaert * @author Frank Dellaert
* @author Stephen Williams * @author Stephen Williams
*/ */

View File

@ -10,9 +10,8 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* testBTree.cpp * @file testBTree.cpp
* * @date Feb 3, 2010
* Created on: Feb 3, 2010
* @author Chris Beall * @author Chris Beall
* @author Frank Dellaert * @author Frank Dellaert
*/ */

View File

@ -9,12 +9,11 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* testDSF.cpp * @file testDSF.cpp
* * @date Mar 26, 2010
* Created on: Mar 26, 2010 * @author nikai
* Author: nikai * @brief unit tests for DSF
* Description: unit tests for DSF
*/ */
#include <iostream> #include <iostream>

View File

@ -9,12 +9,11 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* testDSF.cpp * @file testDSF.cpp
* * @date June 25, 2010
* Created on: June 25, 2010 * @author nikai
* Author: nikai * @brief unit tests for DSF
* Description: unit tests for DSF
*/ */
#include <iostream> #include <iostream>

View File

@ -9,11 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* Cal3Bundler.cpp * @file Cal3Bundler.cpp
* * @date Sep 25, 2010
* Created on: Sep 25, 2010 * @author ydjian
* Author: ydjian
*/ */
#include <gtsam/base/Vector.h> #include <gtsam/base/Vector.h>

View File

@ -9,11 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* Cal3DS2.cpp * @file Cal3DS2.cpp
* * @date Feb 28, 2010
* Created on: Feb 28, 2010 * @author ydjian
* Author: ydjian
*/ */
#include <gtsam/base/Vector.h> #include <gtsam/base/Vector.h>

View File

@ -9,11 +9,11 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* Rot2.cpp * @file Rot2.cpp
* * @date Dec 9, 2009
* Created on: Dec 9, 2009 * @author Frank Dellaert
* Author: Frank Dellaert * @brief 2D Rotations
*/ */
#include <gtsam/geometry/Rot2.h> #include <gtsam/geometry/Rot2.h>

View File

@ -9,11 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* SimpleCamera.cpp * @file SimpleCamera.cpp
* * @date Aug 16, 2009
* Created on: Aug 16, 2009 * @author dellaert
* Author: dellaert
*/ */
#include <gtsam/geometry/SimpleCamera.h> #include <gtsam/geometry/SimpleCamera.h>

View File

@ -9,11 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* StereoPoint2.cpp * @file StereoPoint2.cpp
* * @date Jan 26, 2010
* Created on: Jan 26, 2010 * @author dellaert
* Author: dellaert
*/ */
#include <iostream> #include <iostream>

View File

@ -9,11 +9,11 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* tensorInterface.cpp * @file tensorInterface.cpp
* @brief Interfacing tensors template library and gtsam * @brief Interfacing tensors template library and gtsam
* Created on: Feb 12, 2010 * @date Feb 12, 2010
* @author: Frank Dellaert * @author Frank Dellaert
*/ */
#include <gtsam/geometry/tensorInterface.h> #include <gtsam/geometry/tensorInterface.h>

View File

@ -10,9 +10,9 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* Frank Dellaert * @file testCalibratedCamera.cpp
* brief: test CalibratedCamera class * @author Frank Dellaert
* based on testVSLAMFactor.cpp * @brief test CalibratedCamera class
*/ */
#include <iostream> #include <iostream>

View File

@ -9,10 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* testFundamental.cpp * @file testFundamental.cpp
* @brief try tensor expressions based on http://www.gps.caltech.edu/~walter/FTensor/FTensor.pdf * @brief try tensor expressions based on http://www.gps.caltech.edu/~walter/FTensor/FTensor.pdf
* Created on: Feb 13, 2010 * @date Feb 13, 2010
* @author: Frank Dellaert * @author: Frank Dellaert
*/ */

View File

@ -9,11 +9,11 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* testHomography2.cpp * @file testHomography2.cpp
* @brief Test and estimate 2D homographies * @brief Test and estimate 2D homographies
* Created on: Feb 13, 2010 * @date Feb 13, 2010
* @author: Frank Dellaert * @author Frank Dellaert
*/ */
#include <iostream> #include <iostream>

View File

@ -10,9 +10,9 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* Frank Dellaert * @file testSimpleCamera.cpp
* brief: test SimpleCamera class * @author Frank Dellaert
* based on testVSLAMFactor.cpp * @brief test SimpleCamera class
*/ */
#include <cmath> #include <cmath>

View File

@ -9,11 +9,11 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* testTensors.cpp * @file testTensors.cpp
* @brief try tensor expressions based on http://www.gps.caltech.edu/~walter/FTensor/FTensor.pdf * @brief try tensor expressions based on http://www.gps.caltech.edu/~walter/FTensor/FTensor.pdf
* Created on: Feb 9, 2010 * @date Feb 9, 2010
* @author: Frank Dellaert * @author Frank Dellaert
*/ */
#include <iostream> #include <iostream>

View File

@ -9,9 +9,9 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* ClusterTree-inl.h * @file ClusterTree-inl.h
* Created on: July 13, 2010 * @date July 13, 2010
* @author Kai Ni * @author Kai Ni
* @author Frank Dellaert * @author Frank Dellaert
* @brief: Collects factorgraph fragments defined on variable clusters, arranged in a tree * @brief: Collects factorgraph fragments defined on variable clusters, arranged in a tree

View File

@ -9,9 +9,9 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* ClusterTree.h * @file ClusterTree.h
* Created on: July 13, 2010 * @date July 13, 2010
* @author Kai Ni * @author Kai Ni
* @author Frank Dellaert * @author Frank Dellaert
* @brief: Collects factorgraph fragments defined on variable clusters, arranged in a tree * @brief: Collects factorgraph fragments defined on variable clusters, arranged in a tree

View File

@ -9,12 +9,12 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* JunctionTree-inl.h * @file JunctionTree-inl.h
* Created on: Feb 4, 2010 * @date Feb 4, 2010
* @author Kai Ni * @author Kai Ni
* @author Frank Dellaert * @author Frank Dellaert
* @brief: The junction tree, template bodies * @brief The junction tree, template bodies
*/ */
#pragma once #pragma once

View File

@ -9,9 +9,9 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* JunctionTree.h * @file JunctionTree.h
* Created on: Feb 4, 2010 * @date Feb 4, 2010
* @author Kai Ni * @author Kai Ni
* @author Frank Dellaert * @author Frank Dellaert
* @brief: The junction tree * @brief: The junction tree

View File

@ -9,11 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* SymbolicFactorGraph.cpp * @file SymbolicFactorGraph.cpp
* * @date Oct 29, 2009
* Created on: Oct 29, 2009 * @author Frank Dellaert
* Author: Frank Dellaert
*/ */
#include <boost/make_shared.hpp> #include <boost/make_shared.hpp>

View File

@ -9,11 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* SymbolicFactorGraph.h * @file SymbolicFactorGraph.h
* * @date Oct 29, 2009
* Created on: Oct 29, 2009 * @author Frank Dellaert
* Author: Frank Dellaert
*/ */
#pragma once #pragma once

View File

@ -9,11 +9,11 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* graph.h * @file graph.h
* @brief Graph algorithm using boost library * @brief Graph algorithm using boost library
* @author: Kai Ni * @author: Kai Ni
* Created on: Jan 11, 2010 * @date Jan 11, 2010
*/ */
#pragma once #pragma once

View File

@ -1,8 +1,7 @@
/* /**
* testPermutation.cpp * @file testPermutation.cpp
* * @date Sep 22, 2011
* Created on: Sep 22, 2011 * @author richard
* Author: richard
*/ */
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>

View File

@ -9,11 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* timeSymbolMaps.cpp * @file timeSymbolMaps.cpp
* * @date Jan 20, 2010
* Created on: Jan 20, 2010 * @author richard
* Author: richard
*/ */
#include <boost/unordered_map.hpp> #include <boost/unordered_map.hpp>

View File

@ -10,8 +10,8 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* GaussianJunctionTree.cpp * @file GaussianJunctionTree.cpp
* Created on: Jul 12, 2010 * @date Jul 12, 2010
* @author Kai Ni * @author Kai Ni
* @author Frank Dellaert * @author Frank Dellaert
* @brief: the Gaussian junction tree * @brief: the Gaussian junction tree

View File

@ -10,8 +10,8 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* GaussianJunctionTree.h * @file GaussianJunctionTree.h
* Created on: Jul 12, 2010 * @date Jul 12, 2010
* @author Kai Ni * @author Kai Ni
* @author Frank Dellaert * @author Frank Dellaert
* @brief: the Gaussian junction tree * @brief: the Gaussian junction tree

View File

@ -1,8 +1,7 @@
/* /**
* IterativeOptimizationParameters.h * @file IterativeOptimizationParameters.h
* * @date Oct 22, 2010
* Created on: Oct 22, 2010 * @author Yong-Dian Jian
* Author: Yong-Dian Jian
*/ */
#pragma once #pragma once

View File

@ -9,13 +9,13 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* testKalmanFilter.cpp * @file testKalmanFilter.cpp
* *
* Simple linear Kalman filter. * Simple linear Kalman filter.
* Implemented using factor graphs, i.e., does LDL-based SRIF, really. * Implemented using factor graphs, i.e., does LDL-based SRIF, really.
* *
* Created on: Sep 3, 2011 * @date Sep 3, 2011
* @author Stephen Williams * @author Stephen Williams
* @author Frank Dellaert * @author Frank Dellaert
*/ */

View File

@ -10,10 +10,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* SharedDiagonal.h * @file SharedDiagonal.h
* @brief Class that wraps a shared noise model with diagonal covariance * @brief Class that wraps a shared noise model with diagonal covariance
* @author Frank Dellaert * @author Frank Dellaert
* Created on: Jan 22, 2010 * @date Jan 22, 2010
*/ */
#pragma once #pragma once

View File

@ -10,10 +10,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* SharedGaussian.h * @file SharedGaussian.h
* @brief Class that wraps a shared noise model with diagonal covariance * @brief Class that wraps a shared noise model with diagonal covariance
* @author Frank Dellaert * @author Frank Dellaert
* Created on: Jan 22, 2010 * @date Jan 22, 2010
*/ */
#pragma once #pragma once

View File

@ -9,9 +9,9 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* SubgraphPreconditioner.cpp * @file SubgraphPreconditioner.cpp
* Created on: Dec 31, 2009 * @date Dec 31, 2009
* @author: Frank Dellaert * @author: Frank Dellaert
*/ */

View File

@ -9,10 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* SubgraphPreconditioner.h * @file SubgraphPreconditioner.h
* Created on: Dec 31, 2009 * @date Dec 31, 2009
* @author: Frank Dellaert * @author Frank Dellaert
*/ */
#pragma once #pragma once

View File

@ -9,11 +9,11 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* iterative-inl.h * @file iterative-inl.h
* @brief Iterative methods, template implementation * @brief Iterative methods, template implementation
* @author Frank Dellaert * @author Frank Dellaert
* Created on: Dec 28, 2009 * @date Dec 28, 2009
*/ */
#pragma once #pragma once

View File

@ -9,11 +9,11 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* iterative.cpp * @file iterative.cpp
* @brief Iterative methods, implementation * @brief Iterative methods, implementation
* @author Frank Dellaert * @author Frank Dellaert
* Created on: Dec 28, 2009 * @date Dec 28, 2009
*/ */
#include <iostream> #include <iostream>

View File

@ -9,11 +9,11 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* iterative.h * @file iterative.h
* @brief Iterative methods, implementation * @brief Iterative methods, implementation
* @author Frank Dellaert * @author Frank Dellaert
* Created on: Dec 28, 2009 * @date Dec 28, 2009
*/ */
#pragma once #pragma once

View File

@ -9,10 +9,9 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* testErrors.cpp * @file testErrors.cpp
* * @date Feb 20, 2010
* Created on: Feb 20, 2010
* @author Frank Dellaert * @author Frank Dellaert
*/ */

View File

@ -9,10 +9,9 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* testGaussianJunctionTree.cpp * @file testGaussianJunctionTree.cpp
* * @date Jul 8, 2010
* Created on: Jul 8, 2010
* @author Kai Ni * @author Kai Ni
*/ */

View File

@ -9,12 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* testKalmanFilter.cpp * @file testKalmanFilter.cpp
* * @brief Test simple linear Kalman filter on a moving 2D point
* Test simple linear Kalman filter on a moving 2D point * @date Sep 3, 2011
*
* Created on: Sep 3, 2011
* @author Stephen Williams * @author Stephen Williams
* @author Frank Dellaert * @author Frank Dellaert
*/ */

View File

@ -9,12 +9,11 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* testNoiseModel.cpp * @file testNoiseModel.cpp
* * @date Jan 13, 2010
* Created on: Jan 13, 2010 * @author Richard Roberts
* Author: Richard Roberts * @author Frank Dellaert
* Author: Frank Dellaert
*/ */

View File

@ -11,8 +11,7 @@
/** /**
* @file Key.h * @file Key.h
* * @date Jan 12, 2010
* Created on: Jan 12, 2010
* @author: Frank Dellaert * @author: Frank Dellaert
* @author: Richard Roberts * @author: Richard Roberts
*/ */

View File

@ -10,10 +10,9 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* NonlinearISAM-inl.h * @file NonlinearISAM-inl.h
* * @date Jan 19, 2010
* Created on: Jan 19, 2010 * @author Viorela Ila and Richard Roberts
* Author: Viorela Ila and Richard Roberts
*/ */
#pragma once #pragma once

View File

@ -9,11 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* NonlinearISAM.h * @file NonlinearISAM.h
* * @date Jan 19, 2010
* Created on: Jan 19, 2010 * @author Viorela Ila and Richard Roberts
* Author: Viorela Ila and Richard Roberts
*/ */
#pragma once #pragma once

View File

@ -9,12 +9,11 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* NonlinearOptimization-inl.h * @file NonlinearOptimization-inl.h
* * @date Oct 17, 2010
* Created on: Oct 17, 2010 * @author Kai Ni
* Author: Kai Ni * @brief Easy interfaces for NonlinearOptimizer
* Description: Easy interfaces for NonlinearOptimizer
*/ */
#pragma once #pragma once

View File

@ -9,12 +9,11 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* NonlinearOptimization.h * @file NonlinearOptimization.h
* * @date Oct 14, 2010
* Created on: Oct 14, 2010 * @author Kai Ni
* Author: Kai Ni * @brief Easy interfaces for NonlinearOptimizer
* Description: Easy interfaces for NonlinearOptimizer
*/ */
#pragma once #pragma once

View File

@ -10,12 +10,12 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* NonlinearOptimizer-inl.h * @file NonlinearOptimizer-inl.h
* This is a template definition file, include it where needed (only!) * This is a template definition file, include it where needed (only!)
* so that the appropriate code is generated and link errors avoided. * so that the appropriate code is generated and link errors avoided.
* @brief: Encapsulates nonlinear optimization state * @brief: Encapsulates nonlinear optimization state
* @author Frank Dellaert * @author Frank Dellaert
* Created on: Sep 7, 2009 * @date Sep 7, 2009
*/ */
#pragma once #pragma once

View File

@ -10,10 +10,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* NonlinearOptimizer.cpp * @file NonlinearOptimizer.cpp
* @brief: Convergence functions not dependent on graph types * @brief Convergence functions not dependent on graph types
* @author Frank Dellaert * @author Frank Dellaert
* Created on: Jul 17, 2010 * @date Jul 17, 2010
*/ */
#include <iostream> #include <iostream>

View File

@ -10,10 +10,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* NonlinearOptimizer.h * @file NonlinearOptimizer.h
* @brief: Encapsulates nonlinear optimization state * @brief Encapsulates nonlinear optimization state
* @author Frank Dellaert * @author Frank Dellaert
* Created on: Sep 7, 2009 * @date Sep 7, 2009
*/ */
#pragma once #pragma once

View File

@ -9,12 +9,11 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* BearingRangeFactor.h * @file BearingRangeFactor.h
* * @date Apr 1, 2010
* Created on: Apr 1, 2010 * @author Kai Ni
* Author: Kai Ni * @brief a single factor contains both the bearing and the range to prevent handle to pair bearing and range factors
* Description: a single factor contains both the bearing and the range to prevent handle to pair bearing and range factors
*/ */
#pragma once #pragma once

View File

@ -9,11 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* Simulated2DMeasurement.h * @file Simulated2DMeasurement.h
* * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
* Re-created on Feb 22, 2010 for compatibility with MATLAB * @author Frank Dellaert
* Author: Frank Dellaert
*/ */
#pragma once #pragma once

View File

@ -9,11 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* Simulated2DOdometry.h * @file Simulated2DOdometry.h
* * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
* Re-created on Feb 22, 2010 for compatibility with MATLAB * @author Frank Dellaert
* Author: Frank Dellaert
*/ */
#pragma once #pragma once

View File

@ -9,11 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* Simulated2DOrientedOdometry.h * @file Simulated2DOrientedOdometry.h
* * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
* Re-created on Feb 22, 2010 for compatibility with MATLAB * @author Kai Ni
* Author: Kai Ni
*/ */
#pragma once #pragma once

View File

@ -9,11 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* Simulated2DOrientedPosePrior.h * @file Simulated2DOrientedPosePrior.h
* * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
* Re-created on Feb 22, 2010 for compatibility with MATLAB * @author Kai Ni
* Author: Kai Ni
*/ */
#pragma once #pragma once

View File

@ -9,11 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* Simulated2DValues.h * @file Simulated2DValues.h
* * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
* Re-created on Feb 22, 2010 for compatibility with MATLAB * @author Frank Dellaert
* Author: Frank Dellaert
*/ */
#pragma once #pragma once

View File

@ -9,11 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* Simulated2DPointPrior.h * @file Simulated2DPointPrior.h
* * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
* Re-created on Feb 22, 2010 for compatibility with MATLAB * @author Frank Dellaert
* Author: Frank Dellaert
*/ */
#pragma once #pragma once

View File

@ -9,11 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* Simulated2DPosePrior.h * @file Simulated2DPosePrior.h
* * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
* Re-created on Feb 22, 2010 for compatibility with MATLAB * @author Frank Dellaert
* Author: Frank Dellaert
*/ */
#pragma once #pragma once

View File

@ -9,11 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* Simulated2DValues.h * @file Simulated2DValues.h
* * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
* Re-created on Feb 22, 2010 for compatibility with MATLAB * @author Frank Dellaert
* Author: Frank Dellaert
*/ */
#pragma once #pragma once

View File

@ -9,12 +9,11 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* dataset.cpp * @file dataset.cpp
* * @date Jan 22, 2010
* Created on: Jan 22, 2010 * @author nikai
* Author: nikai * @brief utility functions for loading datasets
* Description: utility functions for loading datasets
*/ */

View File

@ -9,12 +9,11 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* dataset.h * @file dataset.h
* * @date Jan 22, 2010
* Created on: Jan 22, 2010 * @author nikai
* Author: nikai * @brief utility functions for loading datasets
* Description: utility functions for loading datasets
*/ */
#pragma once #pragma once

View File

@ -1,9 +1,8 @@
/* /**
* testGeneralSFMFactor.cpp * @file testGeneralSFMFactor.cpp
* * @date Dec 27, 2010
* Created on: Dec 27, 2010 * @author nikai
* Author: nikai * @brief unit tests for GeneralSFMFactor
* Description: unit tests for GeneralSFMFactor
*/ */
#include <iostream> #include <iostream>

View File

@ -1,9 +1,8 @@
/* /**
* testGeneralSFMFactor.cpp * @file testGeneralSFMFactor.cpp
* * @date Dec 27, 2010
* Created on: Dec 27, 2010 * @author nikai
* Author: nikai * @brief unit tests for GeneralSFMFactor
* Description: unit tests for GeneralSFMFactor
*/ */
#include <iostream> #include <iostream>

View File

@ -9,12 +9,11 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* testSimulated2DOriented.cpp * @file testSimulated2DOriented.cpp
* * @date Jun 10, 2010
* Created on: Jun 10, 2010 * @author nikai
* Author: nikai * @brief unit tests for simulated2DOriented
* Description: unit tests for simulated2DOriented
*/ */
#include <iostream> #include <iostream>

View File

@ -9,11 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* visualSLAM.cpp * @file visualSLAM.cpp
* * @date Jan 14, 2010
* Created on: Jan 14, 2010 * @author richard
* Author: richard
*/ */
#include <gtsam/slam/visualSLAM.h> #include <gtsam/slam/visualSLAM.h>

View File

@ -9,12 +9,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* testGaussianJunctionTree.cpp * @file testGaussianJunctionTree.cpp
* * @date Jul 8, 2010
* Created on: Jul 8, 2010 * @author nikai
* Author: nikai
* Description:
*/ */
#include <iostream> #include <iostream>

View File

@ -9,12 +9,11 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/* /**
* testGraph.cpp * @file testGraph.cpp
* * @date Jan 12, 2010
* Created on: Jan 12, 2010 * @author nikai
* Author: nikai * @brief unit test for graph-inl.h
* Description: unit test for graph-inl.h
*/ */
#include <iostream> #include <iostream>

View File

@ -10,8 +10,8 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* file: Argument.ccp * @file Argument.ccp
* Author: Frank Dellaert * @author Frank Dellaert
**/ **/
#include <iostream> #include <iostream>

View File

@ -10,9 +10,9 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* file: Argument.h * @file Argument.h
* brief: arguments to constructors and methods * @brief arguments to constructors and methods
* Author: Frank Dellaert * @author Frank Dellaert
**/ **/
#pragma once #pragma once

View File

@ -10,8 +10,8 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* file: Class.ccp * @file Class.ccp
* Author: Frank Dellaert * @author Frank Dellaert
**/ **/
#include <iostream> #include <iostream>

View File

@ -10,9 +10,9 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* file: Class.h * @file Class.h
* brief: describe the C++ class that is being wrapped * @brief describe the C++ class that is being wrapped
* Author: Frank Dellaert * @author Frank Dellaert
**/ **/
#pragma once #pragma once

View File

@ -10,8 +10,8 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* file: Constructor.ccp * @file Constructor.ccp
* Author: Frank Dellaert * @author Frank Dellaert
**/ **/
#include <iostream> #include <iostream>

View File

@ -10,9 +10,9 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* file: Constructor.h * @file Constructor.h
* brief: class describing a constructor + code generation * @brief class describing a constructor + code generation
* Author: Frank Dellaert * @author Frank Dellaert
**/ **/
#pragma once #pragma once

View File

@ -10,8 +10,8 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* file: Method.ccp * @file Method.ccp
* Author: Frank Dellaert * @author Frank Dellaert
**/ **/
#include <iostream> #include <iostream>

View File

@ -10,9 +10,9 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* file: Method.h * @file Method.h
* brief: describes and generates code for methods * @brief describes and generates code for methods
* Author: Frank Dellaert * @author Frank Dellaert
**/ **/
#pragma once #pragma once
@ -22,7 +22,7 @@
#include "Argument.h" #include "Argument.h"
// Method class /// Method class
struct Method { struct Method {
bool is_const; bool is_const;
ArgumentList args; ArgumentList args;

View File

@ -10,8 +10,8 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* file: Module.ccp * @file Module.ccp
* Author: Frank Dellaert * @author Frank Dellaert
**/ **/
#include <iostream> #include <iostream>

View File

@ -10,9 +10,9 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* file: Module.h * @file Module.h
* brief: describes module to be wrapped * @brief describes module to be wrapped
* Author: Frank Dellaert * @author Frank Dellaert
**/ **/
#pragma once #pragma once

View File

@ -10,8 +10,9 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* Unit test for Boost's awesome Spirit parser * @file testSpirit.cpp
* Author: Frank Dellaert * @brief Unit test for Boost's awesome Spirit parser
* @author Frank Dellaert
**/ **/
#include <boost/spirit/include/classic_core.hpp> #include <boost/spirit/include/classic_core.hpp>

View File

@ -10,8 +10,9 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* Unit test for wrap.c * @file testWrap.cpp
* Author: Frank Dellaert * @brief Unit test for wrap.c
* @author Frank Dellaert
**/ **/
#include <iostream> #include <iostream>

View File

@ -10,8 +10,8 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* file: utilities.ccp * @file utilities.ccp
* Author: Frank Dellaert * @author Frank Dellaert
**/ **/
#include <iostream> #include <iostream>

View File

@ -10,8 +10,8 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* file: utilities.ccp * @file utilities.ccp
* Author: Frank Dellaert * @author Frank Dellaert
**/ **/
#pragma once #pragma once

View File

@ -10,9 +10,9 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* file: wrap.ccp * @file wrap.ccp
* brief: wraps functions * @brief wraps functions
* Author: Frank Dellaert * @author Frank Dellaert
**/ **/
#include <stdio.h> #include <stdio.h>