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
*
* Created on: Oct 21, 2010
* Author: ydjian
* @date Oct 21, 2010
* @author ydjian
*/
#include <cmath>

View File

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

View File

@ -9,16 +9,16 @@
* -------------------------------------------------------------------------- */
/*
* easyPoint2KalmanFilter.cpp
/**
* @file easyPoint2KalmanFilter.cpp
*
* 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
* operations as in elaboratePoint2KalmanFilter
*
* Created on: Aug 19, 2011
* @author Frank Dellaert
* @author Stephen Williams
* @date Aug 19, 2011
* @author Frank Dellaert
* @author Stephen Williams
*/
#include <gtsam/nonlinear/ExtendedKalmanFilter-inl.h>

View File

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

View File

@ -10,11 +10,10 @@
* -------------------------------------------------------------------------- */
/**
* testBTree.cpp
*
* Created on: Feb 3, 2010
* @author Chris Beall
* @author Frank Dellaert
* @file testBTree.cpp
* @date Feb 3, 2010
* @author Chris Beall
* @author Frank Dellaert
*/
#include <boost/shared_ptr.hpp>

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@ -10,9 +10,9 @@
* -------------------------------------------------------------------------- */
/**
* Frank Dellaert
* brief: test CalibratedCamera class
* based on testVSLAMFactor.cpp
* @file testCalibratedCamera.cpp
* @author Frank Dellaert
* @brief test CalibratedCamera class
*/
#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
* Created on: Feb 13, 2010
* @date Feb 13, 2010
* @author: Frank Dellaert
*/

View File

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

View File

@ -10,9 +10,9 @@
* -------------------------------------------------------------------------- */
/**
* Frank Dellaert
* brief: test SimpleCamera class
* based on testVSLAMFactor.cpp
* @file testSimpleCamera.cpp
* @author Frank Dellaert
* @brief test SimpleCamera class
*/
#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
* Created on: Feb 9, 2010
* @author: Frank Dellaert
* @date Feb 9, 2010
* @author Frank Dellaert
*/
#include <iostream>

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@ -9,11 +9,10 @@
* -------------------------------------------------------------------------- */
/*
* testErrors.cpp
*
* Created on: Feb 20, 2010
* @author Frank Dellaert
/**
* @file testErrors.cpp
* @date Feb 20, 2010
* @author Frank Dellaert
*/
#include <boost/assign/std/list.hpp> // for +=

View File

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

View File

@ -9,14 +9,12 @@
* -------------------------------------------------------------------------- */
/*
* testKalmanFilter.cpp
*
* Test simple linear Kalman filter on a moving 2D point
*
* Created on: Sep 3, 2011
* @author Stephen Williams
* @author Frank Dellaert
/**
* @file testKalmanFilter.cpp
* @brief Test simple linear Kalman filter on a moving 2D point
* @date Sep 3, 2011
* @author Stephen Williams
* @author Frank Dellaert
*/
#include <gtsam/linear/KalmanFilter.h>

View File

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

View File

@ -11,10 +11,9 @@
/**
* @file Key.h
*
* Created on: Jan 12, 2010
* @author: Frank Dellaert
* @author: Richard Roberts
* @date Jan 12, 2010
* @author: Frank Dellaert
* @author: Richard Roberts
*/
#pragma once

View File

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

View File

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

View File

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

View File

@ -9,12 +9,11 @@
* -------------------------------------------------------------------------- */
/*
* NonlinearOptimization.h
*
* Created on: Oct 14, 2010
* Author: Kai Ni
* Description: Easy interfaces for NonlinearOptimizer
/**
* @file NonlinearOptimization.h
* @date Oct 14, 2010
* @author Kai Ni
* @brief Easy interfaces for NonlinearOptimizer
*/
#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!)
* so that the appropriate code is generated and link errors avoided.
* @brief: Encapsulates nonlinear optimization state
* @author Frank Dellaert
* Created on: Sep 7, 2009
* @date Sep 7, 2009
*/
#pragma once

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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