Changed method summaries to lower case
parent
947588586c
commit
9938b4785d
|
@ -332,7 +332,7 @@ void Class::comment_fragment(FileWriter& proxyFile) const
|
|||
{
|
||||
|
||||
string up_name = boost::to_upper_copy(name);
|
||||
proxyFile.oss << "%" << up_name << "(";
|
||||
proxyFile.oss << "%" << name << "(";
|
||||
unsigned int i = 0;
|
||||
BOOST_FOREACH(const Argument& arg, argList)
|
||||
{
|
||||
|
@ -352,7 +352,7 @@ void Class::comment_fragment(FileWriter& proxyFile) const
|
|||
BOOST_FOREACH(ArgumentList argList, m.argLists)
|
||||
{
|
||||
string up_name = boost::to_upper_copy(m.name);
|
||||
proxyFile.oss << "%" << up_name << "(";
|
||||
proxyFile.oss << "%" << m.name << "(";
|
||||
unsigned int i = 0;
|
||||
BOOST_FOREACH(const Argument& arg, argList)
|
||||
{
|
||||
|
@ -373,7 +373,7 @@ void Class::comment_fragment(FileWriter& proxyFile) const
|
|||
BOOST_FOREACH(ArgumentList argList, m.argLists)
|
||||
{
|
||||
string up_name = boost::to_upper_copy(m.name);
|
||||
proxyFile.oss << "%" << up_name << "(";
|
||||
proxyFile.oss << "%" << m.name << "(";
|
||||
unsigned int i = 0;
|
||||
BOOST_FOREACH(const Argument& arg, argList)
|
||||
{
|
||||
|
|
|
@ -1,15 +1,15 @@
|
|||
%-------Constructors-------
|
||||
%POINT2()
|
||||
%POINT2(double x, double y)
|
||||
%Point2()
|
||||
%Point2(double x, double y)
|
||||
%
|
||||
%-------Methods-------
|
||||
%ARGCHAR(char a) : returns void
|
||||
%ARGUCHAR(unsigned char a) : returns void
|
||||
%DIM() : returns int
|
||||
%RETURNCHAR() : returns char
|
||||
%VECTORCONFUSION() : returns VectorNotEigen
|
||||
%X() : returns double
|
||||
%Y() : returns double
|
||||
%argChar(char a) : returns void
|
||||
%argUChar(unsigned char a) : returns void
|
||||
%dim() : returns int
|
||||
%returnChar() : returns char
|
||||
%vectorConfusion() : returns VectorNotEigen
|
||||
%x() : returns double
|
||||
%y() : returns double
|
||||
%
|
||||
%-------Static Methods-------
|
||||
%
|
||||
|
|
|
@ -1,12 +1,12 @@
|
|||
%-------Constructors-------
|
||||
%POINT3(double x, double y, double z)
|
||||
%Point3(double x, double y, double z)
|
||||
%
|
||||
%-------Methods-------
|
||||
%NORM() : returns double
|
||||
%norm() : returns double
|
||||
%
|
||||
%-------Static Methods-------
|
||||
%STATICFUNCTIONRET(double z) : returns Point3
|
||||
%STATICFUNCTION() : returns double
|
||||
%StaticFunctionRet(double z) : returns Point3
|
||||
%staticFunction() : returns double
|
||||
%
|
||||
%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
|
||||
classdef Point3 < handle
|
||||
|
|
|
@ -1,27 +1,27 @@
|
|||
%-------Constructors-------
|
||||
%TEST()
|
||||
%TEST(double a, Matrix b)
|
||||
%Test()
|
||||
%Test(double a, Matrix b)
|
||||
%
|
||||
%-------Methods-------
|
||||
%ARG_EIGENCONSTREF(Matrix value) : returns void
|
||||
%CREATE_MIXEDPTRS() : returns pair< Test, SharedTest >
|
||||
%CREATE_PTRS() : returns pair< SharedTest, SharedTest >
|
||||
%PRINT() : returns void
|
||||
%RETURN_POINT2PTR(bool value) : returns Point2
|
||||
%RETURN_TEST(Test value) : returns Test
|
||||
%RETURN_TESTPTR(Test value) : returns Test
|
||||
%RETURN_BOOL(bool value) : returns bool
|
||||
%RETURN_DOUBLE(double value) : returns double
|
||||
%RETURN_FIELD(Test t) : returns bool
|
||||
%RETURN_INT(int value) : returns int
|
||||
%RETURN_MATRIX1(Matrix value) : returns Matrix
|
||||
%RETURN_MATRIX2(Matrix value) : returns Matrix
|
||||
%RETURN_PAIR(Vector v, Matrix A) : returns pair< Vector, Matrix >
|
||||
%RETURN_PTRS(Test p1, Test p2) : returns pair< SharedTest, SharedTest >
|
||||
%RETURN_SIZE_T(size_t value) : returns size_t
|
||||
%RETURN_STRING(string value) : returns string
|
||||
%RETURN_VECTOR1(Vector value) : returns Vector
|
||||
%RETURN_VECTOR2(Vector value) : returns Vector
|
||||
%arg_EigenConstRef(Matrix value) : returns void
|
||||
%create_MixedPtrs() : returns pair< Test, SharedTest >
|
||||
%create_ptrs() : returns pair< SharedTest, SharedTest >
|
||||
%print() : returns void
|
||||
%return_Point2Ptr(bool value) : returns Point2
|
||||
%return_Test(Test value) : returns Test
|
||||
%return_TestPtr(Test value) : returns Test
|
||||
%return_bool(bool value) : returns bool
|
||||
%return_double(double value) : returns double
|
||||
%return_field(Test t) : returns bool
|
||||
%return_int(int value) : returns int
|
||||
%return_matrix1(Matrix value) : returns Matrix
|
||||
%return_matrix2(Matrix value) : returns Matrix
|
||||
%return_pair(Vector v, Matrix A) : returns pair< Vector, Matrix >
|
||||
%return_ptrs(Test p1, Test p2) : returns pair< SharedTest, SharedTest >
|
||||
%return_size_t(size_t value) : returns size_t
|
||||
%return_string(string value) : returns string
|
||||
%return_vector1(Vector value) : returns Vector
|
||||
%return_vector2(Vector value) : returns Vector
|
||||
%
|
||||
%-------Static Methods-------
|
||||
%
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
%-------Constructors-------
|
||||
%CLASSA()
|
||||
%ClassA()
|
||||
%
|
||||
%-------Methods-------
|
||||
%
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
%-------Constructors-------
|
||||
%CLASSB()
|
||||
%ClassB()
|
||||
%
|
||||
%-------Methods-------
|
||||
%
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
%-------Constructors-------
|
||||
%CLASSB()
|
||||
%ClassB()
|
||||
%
|
||||
%-------Methods-------
|
||||
%
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
%-------Constructors-------
|
||||
%CLASSA()
|
||||
%ClassA()
|
||||
%
|
||||
%-------Methods-------
|
||||
%MEMBERFUNCTION() : returns double
|
||||
%NSARG(ClassB arg) : returns int
|
||||
%NSRETURN(double q) : returns ns2::ns3::ClassB
|
||||
%memberFunction() : returns double
|
||||
%nsArg(ClassB arg) : returns int
|
||||
%nsReturn(double q) : returns ns2::ns3::ClassB
|
||||
%
|
||||
%-------Static Methods-------
|
||||
%AFUNCTION() : returns double
|
||||
%afunction() : returns double
|
||||
%
|
||||
%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
|
||||
classdef ClassA < handle
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
%-------Constructors-------
|
||||
%CLASSC()
|
||||
%ClassC()
|
||||
%
|
||||
%-------Methods-------
|
||||
%
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
%-------Constructors-------
|
||||
%CLASSD()
|
||||
%ClassD()
|
||||
%
|
||||
%-------Methods-------
|
||||
%
|
||||
|
|
Loading…
Reference in New Issue