Removed kwargs overhead for overloaded methods

release/4.3a0
dellaert 2017-08-06 16:53:04 -07:00
parent 8ae9d7c577
commit 81c15d950a
2 changed files with 78 additions and 73 deletions

112
gtsam.h
View File

@ -2,9 +2,13 @@
* GTSAM Wrap Module Definition
*
* These are the current classes available through the matlab toolbox interface,
* These are the current classes available through the matlab and python wrappers,
* add more functions/classes as they are available.
*
* IMPORTANT: the python wrapper supports keyword arguments for functions/methods. Hence, the
* argument names matter. An implementation restriction is that in overloaded methods
* or functions, arguments of different types *have* to have different names.
*
* Requirements:
* Classes must start with an uppercase letter
* - Can wrap a typedef
@ -16,7 +20,7 @@
* - Any class with which be copied with boost::make_shared()
* - boost::shared_ptr of any object type
* Constructors
* - Overloads are supported, but arguments *have* to have different names
* - Overloads are supported, but arguments of different types *have* to have different names
* - A class with no constructors can be returned from other functions but not allocated directly in MATLAB
* Methods
* - Constness has no effect
@ -26,7 +30,7 @@
* Static methods
* - Must start with a letter (upper or lowercase) and use the "static" keyword
* - The first letter will be made uppercase in the generated MATLAB interface
* - Overloads are supported
* - Overloads are supported, but arguments of different types *have* to have different names
* Arguments to functions any of
* - Eigen types: Matrix, Vector
* - Eigen types and classes as an optionally const reference
@ -601,23 +605,23 @@ class Pose3 {
// Group
static gtsam::Pose3 identity();
gtsam::Pose3 inverse() const;
gtsam::Pose3 compose(const gtsam::Pose3& p2) const;
gtsam::Pose3 between(const gtsam::Pose3& p2) const;
gtsam::Pose3 compose(const gtsam::Pose3& pose) const;
gtsam::Pose3 between(const gtsam::Pose3& pose) const;
// Manifold
gtsam::Pose3 retract(Vector v) const;
Vector localCoordinates(const gtsam::Pose3& T2) const;
Vector localCoordinates(const gtsam::Pose3& pose) const;
// Lie Group
static gtsam::Pose3 Expmap(Vector v);
static Vector Logmap(const gtsam::Pose3& p);
static Vector Logmap(const gtsam::Pose3& pose);
Matrix AdjointMap() const;
Vector Adjoint(Vector xi) const;
static Matrix wedge(double wx, double wy, double wz, double vx, double vy, double vz);
// Group Action on Point3
gtsam::Point3 transform_from(const gtsam::Point3& p) const;
gtsam::Point3 transform_to(const gtsam::Point3& p) const;
gtsam::Point3 transform_from(const gtsam::Point3& point) const;
gtsam::Point3 transform_to(const gtsam::Point3& point) const;
// Standard Interface
gtsam::Rot3 rotation() const;
@ -642,7 +646,7 @@ class Pose3Vector
size_t size() const;
bool empty() const;
gtsam::Pose3 at(size_t n) const;
void push_back(const gtsam::Pose3& x);
void push_back(const gtsam::Pose3& pose);
};
#include <gtsam/geometry/Unit3.h>
@ -915,7 +919,7 @@ class PinholeCamera {
gtsam::Point2 project(const gtsam::Point3& point);
gtsam::Point3 backproject(const gtsam::Point2& p, double depth) const;
double range(const gtsam::Point3& point);
double range(const gtsam::Pose3& point);
double range(const gtsam::Pose3& pose);
// enabling serialization functionality
void serialize() const;
@ -952,7 +956,7 @@ virtual class SimpleCamera {
gtsam::Point2 project(const gtsam::Point3& point);
gtsam::Point3 backproject(const gtsam::Point2& p, double depth) const;
double range(const gtsam::Point3& point);
double range(const gtsam::Pose3& point);
double range(const gtsam::Pose3& pose);
// enabling serialization functionality
void serialize() const;
@ -1066,13 +1070,13 @@ virtual class SymbolicFactorGraph {
const gtsam::Ordering& ordering);
pair<gtsam::SymbolicBayesTree*, gtsam::SymbolicFactorGraph*> eliminatePartialMultifrontal(
const gtsam::KeyVector& keys);
gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet(const gtsam::Ordering& variables);
gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet(const gtsam::KeyVector& variables);
gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet(const gtsam::Ordering& variables,
gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet(const gtsam::Ordering& ordering);
gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet(const gtsam::KeyVector& key_vector);
gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet(const gtsam::Ordering& ordering,
const gtsam::Ordering& marginalizedVariableOrdering);
gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet(const gtsam::KeyVector& variables,
gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet(const gtsam::KeyVector& key_vector,
const gtsam::Ordering& marginalizedVariableOrdering);
gtsam::SymbolicFactorGraph* marginal(const gtsam::KeyVector& variables);
gtsam::SymbolicFactorGraph* marginal(const gtsam::KeyVector& key_vector);
};
#include <gtsam/symbolic/SymbolicConditional.h>
@ -1466,7 +1470,7 @@ class GaussianFactorGraph {
// Building the graph
void push_back(const gtsam::GaussianFactor* factor);
void push_back(const gtsam::GaussianConditional* factor);
void push_back(const gtsam::GaussianConditional* conditional);
void push_back(const gtsam::GaussianFactorGraph& graph);
void push_back(const gtsam::GaussianBayesNet& bayesNet);
void push_back(const gtsam::GaussianBayesTree& bayesTree);
@ -1505,13 +1509,13 @@ class GaussianFactorGraph {
const gtsam::Ordering& ordering);
pair<gtsam::GaussianBayesTree*, gtsam::GaussianFactorGraph*> eliminatePartialMultifrontal(
const gtsam::KeyVector& keys);
gtsam::GaussianBayesNet* marginalMultifrontalBayesNet(const gtsam::Ordering& variables);
gtsam::GaussianBayesNet* marginalMultifrontalBayesNet(const gtsam::KeyVector& variables);
gtsam::GaussianBayesNet* marginalMultifrontalBayesNet(const gtsam::Ordering& variables,
gtsam::GaussianBayesNet* marginalMultifrontalBayesNet(const gtsam::Ordering& ordering);
gtsam::GaussianBayesNet* marginalMultifrontalBayesNet(const gtsam::KeyVector& key_vector);
gtsam::GaussianBayesNet* marginalMultifrontalBayesNet(const gtsam::Ordering& ordering,
const gtsam::Ordering& marginalizedVariableOrdering);
gtsam::GaussianBayesNet* marginalMultifrontalBayesNet(const gtsam::KeyVector& variables,
gtsam::GaussianBayesNet* marginalMultifrontalBayesNet(const gtsam::KeyVector& key_vector,
const gtsam::Ordering& marginalizedVariableOrdering);
gtsam::GaussianFactorGraph* marginal(const gtsam::KeyVector& variables);
gtsam::GaussianFactorGraph* marginal(const gtsam::KeyVector& key_vector);
// Conversion to matrices
Matrix sparseJacobian_() const;
@ -1865,34 +1869,34 @@ class Values {
// void update(size_t j, const gtsam::Value& val);
// gtsam::Value at(size_t j) const;
void insert(size_t j, const gtsam::Point2& t);
void insert(size_t j, const gtsam::Point3& t);
void insert(size_t j, const gtsam::Rot2& t);
void insert(size_t j, const gtsam::Pose2& t);
void insert(size_t j, const gtsam::Rot3& t);
void insert(size_t j, const gtsam::Pose3& t);
void insert(size_t j, const gtsam::Cal3_S2& t);
void insert(size_t j, const gtsam::Cal3DS2& t);
void insert(size_t j, const gtsam::Cal3Bundler& t);
void insert(size_t j, const gtsam::EssentialMatrix& t);
void insert(size_t j, const gtsam::SimpleCamera& t);
void insert(size_t j, const gtsam::imuBias::ConstantBias& t);
void insert(size_t j, Vector t);
void insert(size_t j, Matrix t);
void insert(size_t j, const gtsam::Point2& point2);
void insert(size_t j, const gtsam::Point3& point3);
void insert(size_t j, const gtsam::Rot2& rot2);
void insert(size_t j, const gtsam::Pose2& pose2);
void insert(size_t j, const gtsam::Rot3& rot3);
void insert(size_t j, const gtsam::Pose3& pose3);
void insert(size_t j, const gtsam::Cal3_S2& cal3_s2);
void insert(size_t j, const gtsam::Cal3DS2& cal3ds2);
void insert(size_t j, const gtsam::Cal3Bundler& cal3bundler);
void insert(size_t j, const gtsam::EssentialMatrix& essential_matrix);
void insert(size_t j, const gtsam::SimpleCamera& simpel_camera);
void insert(size_t j, const gtsam::imuBias::ConstantBias& constant_bias);
void insert(size_t j, Vector vector);
void insert(size_t j, Matrix matrix);
void update(size_t j, const gtsam::Point2& t);
void update(size_t j, const gtsam::Point3& t);
void update(size_t j, const gtsam::Rot2& t);
void update(size_t j, const gtsam::Pose2& t);
void update(size_t j, const gtsam::Rot3& t);
void update(size_t j, const gtsam::Pose3& t);
void update(size_t j, const gtsam::Cal3_S2& t);
void update(size_t j, const gtsam::Cal3DS2& t);
void update(size_t j, const gtsam::Cal3Bundler& t);
void update(size_t j, const gtsam::EssentialMatrix& t);
void update(size_t j, const gtsam::imuBias::ConstantBias& t);
void update(size_t j, Vector t);
void update(size_t j, Matrix t);
void update(size_t j, const gtsam::Point2& point2);
void update(size_t j, const gtsam::Point3& point3);
void update(size_t j, const gtsam::Rot2& rot2);
void update(size_t j, const gtsam::Pose2& pose2);
void update(size_t j, const gtsam::Rot3& rot3);
void update(size_t j, const gtsam::Pose3& pose3);
void update(size_t j, const gtsam::Cal3_S2& cal3_s2);
void update(size_t j, const gtsam::Cal3DS2& cal3ds2);
void update(size_t j, const gtsam::Cal3Bundler& cal3bundler);
void update(size_t j, const gtsam::EssentialMatrix& essential_matrix);
void update(size_t j, const gtsam::imuBias::ConstantBias& constant_bias);
void update(size_t j, Vector vector);
void update(size_t j, Matrix matrix);
template<T = {gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::Pose2, gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::Cal3Bundler, gtsam::EssentialMatrix, gtsam::imuBias::ConstantBias, Vector, Matrix}>
T at(size_t j);
@ -2106,10 +2110,10 @@ class ISAM2Params {
void print(string str) const;
/** Getters and Setters for all properties */
void setOptimizationParams(const gtsam::ISAM2GaussNewtonParams& params);
void setOptimizationParams(const gtsam::ISAM2DoglegParams& params);
void setRelinearizeThreshold(double relinearizeThreshold);
void setRelinearizeThreshold(const gtsam::ISAM2ThresholdMap& relinearizeThreshold);
void setOptimizationParams(const gtsam::ISAM2GaussNewtonParams& gauss_newton__params);
void setOptimizationParams(const gtsam::ISAM2DoglegParams& dogleg_params);
void setRelinearizeThreshold(double threshold);
void setRelinearizeThreshold(const gtsam::ISAM2ThresholdMap& threshold_map);
int getRelinearizeSkip() const;
void setRelinearizeSkip(int relinearizeSkip);
bool isEnableRelinearization() const;

View File

@ -141,7 +141,8 @@ void Method::emit_cython_pyx(FileWriter& file, const Class& cls) const {
// doesn't allow overloads
// e.g. template<T={A,B,C}> funcName(...) --> funcNameA, funcNameB, funcNameC
string instantiatedName =
(templateArgValue_) ? funcName + templateArgValue_->pyxClassName() : funcName;
(templateArgValue_) ? funcName + templateArgValue_->pyxClassName() :
funcName;
size_t N = nrOverloads();
// It's easy if there's no overload
@ -152,38 +153,38 @@ void Method::emit_cython_pyx(FileWriter& file, const Class& cls) const {
// Dealing with overloads..
file.oss << " def " << instantiatedName << "(self, *args, **kwargs):\n";
for (size_t i = 0; i < N; ++i) {
file.oss << " success, results = self." << instantiatedName << "_" << i
<< "(args, kwargs)\n";
file.oss << " if success:\n return results\n";
}
file.oss << " raise TypeError('Could not find the correct overload')\n";
file.oss << " cdef list __params\n";
for (size_t i = 0; i < N; ++i) {
ArgumentList args = argumentList(i);
file.oss << " def " + instantiatedName + "_" + to_string(i) +
"(self, args, kwargs):\n";
file.oss << " cdef list __params\n";
// Define return values for all possible overloads
vector<string> return_value;
for (size_t i = 0; i < nrOverloads(); ++i) {
return_value.push_back("return_value_" + to_string(i));
if (!returnVals_[i].isVoid()) {
file.oss << " cdef " << returnVals_[i].pyx_returnType() << " return_value\n";
file.oss << " cdef " << returnVals_[i].pyx_returnType() << " "
<< return_value[i] << "\n";
}
}
for (size_t i = 0; i < nrOverloads(); ++i) {
ArgumentList args = argumentList(i);
file.oss << " try:\n";
file.oss << pyx_resolveOverloadParams(args, false, 3); // lazy: always return None even if it's a void function
/// Call corresponding cython function
file.oss << argumentList(i).pyx_convertEigenTypeAndStorageOrder(" ");
file.oss << args.pyx_convertEigenTypeAndStorageOrder(" ");
string caller = "self." + cls.shared_pxd_obj_in_pyx() + ".get()";
string call = pyx_functionCall(caller, funcName, i);
if (!returnVals_[i].isVoid()) {
file.oss << " return_value = " << call << "\n";
file.oss << " return True, " << returnVals_[i].pyx_casting("return_value") << "\n";
file.oss << " " << return_value[i] << " = " << call << "\n";
file.oss << " return "
<< returnVals_[i].pyx_casting(return_value[i]) << "\n";
} else {
file.oss << " " << call << "\n";
file.oss << " return True, None\n";
file.oss << " return\n";
}
file.oss << " except:\n";
file.oss << " return False, None\n\n";
file.oss << " pass\n";
}
file.oss
<< " raise TypeError('Incorrect arguments for method call.')\n\n";
}
/* ************************************************************************* */