From d8a6b6a5e4f50301641c8ad064ff9367326bc5d7 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 8 Sep 2012 05:44:26 +0000 Subject: [PATCH] Vastly improved "help gtsam" and "doc gtsam" output --- matlab/+gtsam/Contents.m | 161 +++++++++++++++++++++++++++++++++++++++ wrap/Class.cpp | 131 ++++++++++++++++--------------- 2 files changed, 226 insertions(+), 66 deletions(-) create mode 100644 matlab/+gtsam/Contents.m diff --git a/matlab/+gtsam/Contents.m b/matlab/+gtsam/Contents.m new file mode 100644 index 000000000..0af19e1c8 --- /dev/null +++ b/matlab/+gtsam/Contents.m @@ -0,0 +1,161 @@ +% GTSAM MATLAB toolbox interface to the Georgia Tech Smoothing and Mapping C++ library +% Version 2.1 08-Sep-2012 +% +%% Basic Utilities +% linear_independent - check whether the rows of two matrices are linear independent +% Permutation - class Permutation, see Doxygen page for details +% +%% General Inference Classes +% IndexConditional - class IndexConditional, see Doxygen page for details +% IndexFactor - class IndexFactor, see Doxygen page for details +% SymbolicBayesNet - class SymbolicBayesNet, see Doxygen page for details +% SymbolicBayesTree - class SymbolicBayesTree, see Doxygen page for details +% SymbolicFactorGraph - class SymbolicFactorGraph, see Doxygen page for details +% SymbolicMultifrontalSolver - class SymbolicMultifrontalSolver, see Doxygen page for details +% SymbolicSequentialSolver - class SymbolicSequentialSolver, see Doxygen page for details +% VariableIndex - class VariableIndex, see Doxygen page for details +% +%% Linear-Gaussian Factor Graphs +% Errors - class Errors, see Doxygen page for details +% GaussianBayesNet - class GaussianBayesNet, see Doxygen page for details +% GaussianConditional - class GaussianConditional, see Doxygen page for details +% GaussianDensity - class GaussianDensity, see Doxygen page for details +% GaussianFactor - class GaussianFactor, see Doxygen page for details +% GaussianFactorGraph - class GaussianFactorGraph, see Doxygen page for details +% GaussianISAM - class GaussianISAM, see Doxygen page for details +% HessianFactor - class HessianFactor, see Doxygen page for details +% JacobianFactor - class JacobianFactor, see Doxygen page for details +% VectorValues - class VectorValues, see Doxygen page for details +% +%% Linear Inference +% GaussianSequentialSolver - class GaussianSequentialSolver, see Doxygen page for details +% IterativeOptimizationParameters - class IterativeOptimizationParameters, see Doxygen page for details +% KalmanFilter - class KalmanFilter, see Doxygen page for details +% SubgraphSolver - class SubgraphSolver, see Doxygen page for details +% SubgraphSolverParameters - class SubgraphSolverParameters, see Doxygen page for details +% SuccessiveLinearizationParams - class SuccessiveLinearizationParams, see Doxygen page for details +% Sampler - class Sampler, see Doxygen page for details +% +%% Nonlinear Factor Graphs +% NonlinearFactor - class NonlinearFactor, see Doxygen page for details +% NonlinearFactorGraph - class NonlinearFactorGraph, see Doxygen page for details +% Ordering - class Ordering, see Doxygen page for details +% Value - class Value, see Doxygen page for details +% Values - class Values, see Doxygen page for details +% +%% Nonlinear Optimization +% ConjugateGradientParameters - class ConjugateGradientParameters, see Doxygen page for details +% DoglegOptimizer - class DoglegOptimizer, see Doxygen page for details +% DoglegParams - class DoglegParams, see Doxygen page for details +% GaussNewtonOptimizer - class GaussNewtonOptimizer, see Doxygen page for details +% GaussNewtonParams - class GaussNewtonParams, see Doxygen page for details +% ISAM2 - class ISAM2, see Doxygen page for details +% ISAM2DoglegParams - class ISAM2DoglegParams, see Doxygen page for details +% ISAM2GaussNewtonParams - class ISAM2GaussNewtonParams, see Doxygen page for details +% ISAM2Params - class ISAM2Params, see Doxygen page for details +% ISAM2Result - class ISAM2Result, see Doxygen page for details +% ISAM2ThresholdMap - class ISAM2ThresholdMap, see Doxygen page for details +% ISAM2ThresholdMapValue - class ISAM2ThresholdMapValue, see Doxygen page for details +% InvertedOrdering - class InvertedOrdering, see Doxygen page for details +% JointMarginal - class JointMarginal, see Doxygen page for details +% KeyList - class KeyList, see Doxygen page for details +% KeySet - class KeySet, see Doxygen page for details +% KeyVector - class KeyVector, see Doxygen page for details +% LevenbergMarquardtOptimizer - class LevenbergMarquardtOptimizer, see Doxygen page for details +% LevenbergMarquardtParams - class LevenbergMarquardtParams, see Doxygen page for details +% Marginals - class Marginals, see Doxygen page for details +% NonlinearISAM - class NonlinearISAM, see Doxygen page for details +% NonlinearOptimizer - class NonlinearOptimizer, see Doxygen page for details +% NonlinearOptimizerParams - class NonlinearOptimizerParams, see Doxygen page for details +% +%% Geometry +% Cal3_S2 - class Cal3_S2, see Doxygen page for details +% Cal3_S2Stereo - class Cal3_S2Stereo, see Doxygen page for details +% Cal3DS2 - class Cal3DS2, see Doxygen page for details +% CalibratedCamera - class CalibratedCamera, see Doxygen page for details +% Point2 - class Point2, see Doxygen page for details +% Point3 - class Point3, see Doxygen page for details +% Pose2 - class Pose2, see Doxygen page for details +% Pose3 - class Pose3, see Doxygen page for details +% Rot2 - class Rot2, see Doxygen page for details +% Rot3 - class Rot3, see Doxygen page for details +% SimpleCamera - class SimpleCamera, see Doxygen page for details +% StereoPoint2 - class StereoPoint2, see Doxygen page for details +% +%% SLAM and SFM +% BearingFactor2D - class BearingFactor2D, see Doxygen page for details +% BearingRangeFactor2D - class BearingRangeFactor2D, see Doxygen page for details +% BetweenFactorLieMatrix - class BetweenFactorLieMatrix, see Doxygen page for details +% BetweenFactorLieScalar - class BetweenFactorLieScalar, see Doxygen page for details +% BetweenFactorLieVector - class BetweenFactorLieVector, see Doxygen page for details +% BetweenFactorPoint2 - class BetweenFactorPoint2, see Doxygen page for details +% BetweenFactorPoint3 - class BetweenFactorPoint3, see Doxygen page for details +% BetweenFactorPose2 - class BetweenFactorPose2, see Doxygen page for details +% BetweenFactorPose3 - class BetweenFactorPose3, see Doxygen page for details +% BetweenFactorRot2 - class BetweenFactorRot2, see Doxygen page for details +% BetweenFactorRot3 - class BetweenFactorRot3, see Doxygen page for details +% GeneralSFMFactor2Cal3_S2 - class GeneralSFMFactor2Cal3_S2, see Doxygen page for details +% GeneralSFMFactorCal3_S2 - class GeneralSFMFactorCal3_S2, see Doxygen page for details +% GenericProjectionFactorCal3_S2 - class GenericProjectionFactorCal3_S2, see Doxygen page for details +% GenericStereoFactor3D - class GenericStereoFactor3D, see Doxygen page for details +% NonlinearEqualityCal3_S2 - class NonlinearEqualityCal3_S2, see Doxygen page for details +% NonlinearEqualityCalibratedCamera - class NonlinearEqualityCalibratedCamera, see Doxygen page for details +% NonlinearEqualityLieMatrix - class NonlinearEqualityLieMatrix, see Doxygen page for details +% NonlinearEqualityLieScalar - class NonlinearEqualityLieScalar, see Doxygen page for details +% NonlinearEqualityLieVector - class NonlinearEqualityLieVector, see Doxygen page for details +% NonlinearEqualityPoint2 - class NonlinearEqualityPoint2, see Doxygen page for details +% NonlinearEqualityPoint3 - class NonlinearEqualityPoint3, see Doxygen page for details +% NonlinearEqualityPose2 - class NonlinearEqualityPose2, see Doxygen page for details +% NonlinearEqualityPose3 - class NonlinearEqualityPose3, see Doxygen page for details +% NonlinearEqualityRot2 - class NonlinearEqualityRot2, see Doxygen page for details +% NonlinearEqualityRot3 - class NonlinearEqualityRot3, see Doxygen page for details +% NonlinearEqualitySimpleCamera - class NonlinearEqualitySimpleCamera, see Doxygen page for details +% NonlinearEqualityStereoPoint2 - class NonlinearEqualityStereoPoint2, see Doxygen page for details +% PriorFactorCal3_S2 - class PriorFactorCal3_S2, see Doxygen page for details +% PriorFactorCalibratedCamera - class PriorFactorCalibratedCamera, see Doxygen page for details +% PriorFactorLieMatrix - class PriorFactorLieMatrix, see Doxygen page for details +% PriorFactorLieScalar - class PriorFactorLieScalar, see Doxygen page for details +% PriorFactorLieVector - class PriorFactorLieVector, see Doxygen page for details +% PriorFactorPoint2 - class PriorFactorPoint2, see Doxygen page for details +% PriorFactorPoint3 - class PriorFactorPoint3, see Doxygen page for details +% PriorFactorPose2 - class PriorFactorPose2, see Doxygen page for details +% PriorFactorPose3 - class PriorFactorPose3, see Doxygen page for details +% PriorFactorRot2 - class PriorFactorRot2, see Doxygen page for details +% PriorFactorRot3 - class PriorFactorRot3, see Doxygen page for details +% PriorFactorSimpleCamera - class PriorFactorSimpleCamera, see Doxygen page for details +% PriorFactorStereoPoint2 - class PriorFactorStereoPoint2, see Doxygen page for details +% RangeFactorCalibratedCamera - class RangeFactorCalibratedCamera, see Doxygen page for details +% RangeFactorCalibratedCameraPoint - class RangeFactorCalibratedCameraPoint, see Doxygen page for details +% RangeFactorPose2 - class RangeFactorPose2, see Doxygen page for details +% RangeFactorPose3 - class RangeFactorPose3, see Doxygen page for details +% RangeFactorPosePoint2 - class RangeFactorPosePoint2, see Doxygen page for details +% RangeFactorPosePoint3 - class RangeFactorPosePoint3, see Doxygen page for details +% RangeFactorSimpleCamera - class RangeFactorSimpleCamera, see Doxygen page for details +% RangeFactorSimpleCameraPoint - class RangeFactorSimpleCameraPoint, see Doxygen page for details +% VisualISAMGenerateData - VisualISAMGenerateData creates data for viusalSLAM::iSAM examples +% VisualISAMInitialize - VisualISAMInitialize initializes visualSLAM::iSAM object and noise parameters +% VisualISAMPlot - VisualISAMPlot plots current state of ISAM2 object +% VisualISAMStep - VisualISAMStep executes one update step of visualSLAM::iSAM object +% +%% MATLAB-only Utilities +% CHECK - throw an error if an assertion fails +% circlePose2 - circlePose2 generates a set of poses in a circle. This function +% circlePose3 - circlePose3 generates a set of poses in a circle. This function +% covarianceEllipse - covarianceEllipse plots a Gaussian as an uncertainty ellipse +% covarianceEllipse3D - covarianceEllipse3D plots a Gaussian as an uncertainty ellipse +% EQUALITY - test equality of two vectors/matrices up to tolerance +% findExampleDataFile - Find a dataset in the examples folder +% load2D - load2D reads a TORO-style 2D pose graph +% load3D - load3D reads a TORO-style 3D pose graph +% plot2DPoints - Plots the Point2's in a values, with optional covariances +% plot2DTrajectory - Plots the Pose2's in a values, with optional covariances +% plot3DPoints - Plots the Point3's in a values, with optional covariances +% plot3DTrajectory - plot3DTrajectory plots a 3D trajectory +% plotCamera - +% plotPoint2 - plotPoint2 shows a Point2, possibly with covariance matrix +% plotPoint3 - Plot a Point3 with an optional covariance matrix +% plotPose2 - plotPose2 shows a Pose2, possibly with covariance matrix +% plotPose3 - plotPose3 shows a Pose, possibly with covariance matrix +% symbol - create a Symbol key +% symbolChr - get character from a symbol key +% symbolIndex - get index from a symbol key diff --git a/wrap/Class.cpp b/wrap/Class.cpp index 374324558..48fbeb6bf 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -58,13 +58,13 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName, const string parent = qualifiedParent.empty() ? "handle" : matlabBaseName; comment_fragment(proxyFile); proxyFile.oss << "classdef " << name << " < " << parent << endl; - proxyFile.oss << " properties" << endl; - proxyFile.oss << " ptr_" << matlabUniqueName << " = 0" << endl; - proxyFile.oss << " end" << endl; - proxyFile.oss << " methods" << endl; + proxyFile.oss << " properties\n"; + proxyFile.oss << " ptr_" << matlabUniqueName << " = 0\n"; + proxyFile.oss << " end\n"; + proxyFile.oss << " methods\n"; // Constructor - proxyFile.oss << " function obj = " << name << "(varargin)" << endl; + proxyFile.oss << " function obj = " << name << "(varargin)\n"; // Special pointer constructors - one in MATLAB to create an object and // assign a pointer returned from a C++ function. In turn this MATLAB // constructor calls a special C++ function that just adds the object to @@ -85,7 +85,7 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName, functionNames.push_back(wrapFunctionName); } proxyFile.oss << " else\n"; - proxyFile.oss << " error('Arguments do not match any overload of " << matlabQualName << " constructor');" << endl; + proxyFile.oss << " error('Arguments do not match any overload of " << matlabQualName << " constructor');\n"; proxyFile.oss << " end\n"; if(!qualifiedParent.empty()) proxyFile.oss << " obj = obj@" << matlabBaseName << "(uint64(" << ptr_constructor_key << "), base_ptr);\n"; @@ -124,8 +124,8 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName, wrapperFile.oss << "\n"; } - proxyFile.oss << " end" << endl; - proxyFile.oss << "end" << endl; + proxyFile.oss << " end\n"; + proxyFile.oss << "end\n"; // Close file proxyFile.emit(true); @@ -181,7 +181,7 @@ void Class::pointer_constructor_fragments(FileWriter& proxyFile, FileWriter& wra // comes from a C++ return value; this mechanism allows the object to be added // to a collector in a different wrap module. If this class has a base class, // a new pointer to the base class is allocated and returned. - wrapperFile.oss << "void " << collectorInsertFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl; + wrapperFile.oss << "void " << collectorInsertFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; wrapperFile.oss << "{\n"; wrapperFile.oss << " mexAtExit(&_deleteAllObjects);\n"; // Typedef boost::shared_ptr @@ -325,70 +325,69 @@ std::string Class::getTypedef() const { /* ************************************************************************* */ -void Class::comment_fragment(FileWriter& proxyFile) const -{ - proxyFile.oss << "%" << "-------Constructors-------" << endl; - BOOST_FOREACH(ArgumentList argList, constructor.args_list) - { +void Class::comment_fragment(FileWriter& proxyFile) const { + proxyFile.oss << "%class " << name + << ", see Doxygen page for details\n"; + proxyFile.oss + << "%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html\n"; - string up_name = boost::to_upper_copy(name); - proxyFile.oss << "%" << name << "("; - unsigned int i = 0; - BOOST_FOREACH(const Argument& arg, argList) - { - if(i != argList.size()-1) - proxyFile.oss << arg.type << " " << arg.name << ", "; - else - proxyFile.oss << arg.type << " " << arg.name; - i++; - } - proxyFile.oss << ")" << endl; + if (!constructor.args_list.empty()) + proxyFile.oss << "%\n%-------Constructors-------\n"; + BOOST_FOREACH(ArgumentList argList, constructor.args_list) { + string up_name = boost::to_upper_copy(name); + proxyFile.oss << "%" << name << "("; + unsigned int i = 0; + BOOST_FOREACH(const Argument& arg, argList) { + if (i != argList.size() - 1) + proxyFile.oss << arg.type << " " << arg.name << ", "; + else + proxyFile.oss << arg.type << " " << arg.name; + i++; } + proxyFile.oss << ")\n"; + } - proxyFile.oss << "% " << "" << endl; - proxyFile.oss << "%" << "-------Methods-------" << endl; - BOOST_FOREACH(const Methods::value_type& name_m, methods) { - const Method& m = name_m.second; - BOOST_FOREACH(ArgumentList argList, m.argLists) - { - string up_name = boost::to_upper_copy(m.name); - proxyFile.oss << "%" << m.name << "("; - unsigned int i = 0; - BOOST_FOREACH(const Argument& arg, argList) - { - if(i != argList.size()-1) - proxyFile.oss << arg.type << " " << arg.name << ", "; - else - proxyFile.oss << arg.type << " " << arg.name; - i++; - } - proxyFile.oss << ") : returns " << m.returnVals[0].return_type(false, m.returnVals[0].pair) << endl; - } + if (!methods.empty()) + proxyFile.oss << "%\n%-------Methods-------\n"; + BOOST_FOREACH(const Methods::value_type& name_m, methods) { + const Method& m = name_m.second; + BOOST_FOREACH(ArgumentList argList, m.argLists) { + string up_name = boost::to_upper_copy(m.name); + proxyFile.oss << "%" << m.name << "("; + unsigned int i = 0; + BOOST_FOREACH(const Argument& arg, argList) { + if (i != argList.size() - 1) + proxyFile.oss << arg.type << " " << arg.name << ", "; + else + proxyFile.oss << arg.type << " " << arg.name; + i++; + } + proxyFile.oss << ") : returns " + << m.returnVals[0].return_type(false, m.returnVals[0].pair) << endl; } + } - proxyFile.oss << "% " << "" << endl; - proxyFile.oss << "%" << "-------Static Methods-------" << endl; - BOOST_FOREACH(const StaticMethods::value_type& name_m, static_methods) { - const StaticMethod& m = name_m.second; - BOOST_FOREACH(ArgumentList argList, m.argLists) - { - string up_name = boost::to_upper_copy(m.name); - proxyFile.oss << "%" << m.name << "("; - unsigned int i = 0; - BOOST_FOREACH(const Argument& arg, argList) - { - if(i != argList.size()-1) - proxyFile.oss << arg.type << " " << arg.name << ", "; - else - proxyFile.oss << arg.type << " " << arg.name; - i++; - } + if (!static_methods.empty()) + proxyFile.oss << "%\n%-------Static Methods-------\n"; + BOOST_FOREACH(const StaticMethods::value_type& name_m, static_methods) { + const StaticMethod& m = name_m.second; + BOOST_FOREACH(ArgumentList argList, m.argLists) { + string up_name = boost::to_upper_copy(m.name); + proxyFile.oss << "%" << m.name << "("; + unsigned int i = 0; + BOOST_FOREACH(const Argument& arg, argList) { + if (i != argList.size() - 1) + proxyFile.oss << arg.type << " " << arg.name << ", "; + else + proxyFile.oss << arg.type << " " << arg.name; + i++; + } - proxyFile.oss << ") : returns " << m.returnVals[0].return_type(false, m.returnVals[0].pair) << endl; - } + proxyFile.oss << ") : returns " + << m.returnVals[0].return_type(false, m.returnVals[0].pair) << endl; } + } - proxyFile.oss << "%" << "" << endl; - proxyFile.oss << "%" << "For more detailed documentation on GTSAM go to our Doxygen page, which can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html" << endl; + proxyFile.oss << "%\n"; } /* ************************************************************************* */