Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Wrapper Update #1317

Merged
merged 9 commits into from
Oct 29, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions gtsam/geometry/geometry.i
Original file line number Diff line number Diff line change
Expand Up @@ -1123,7 +1123,7 @@ class StereoCamera {
#include <gtsam/geometry/triangulation.h>
class TriangulationResult {
enum Status { VALID, DEGENERATE, BEHIND_CAMERA, OUTLIER, FAR_POINT };
Status status;
gtsam::TriangulationResult::Status status;
TriangulationResult(const gtsam::Point3& p);
const gtsam::Point3& get() const;
static gtsam::TriangulationResult Degenerate();
Expand All @@ -1142,7 +1142,7 @@ class TriangulationParameters {
bool enableEPI;
double landmarkDistanceThreshold;
double dynamicOutlierRejectionThreshold;
SharedNoiseModel noiseModel;
gtsam::SharedNoiseModel noiseModel;
TriangulationParameters(const double rankTolerance = 1.0,
const bool enableEPI = false,
double landmarkDistanceThreshold = -1,
Expand Down
2 changes: 1 addition & 1 deletion gtsam/inference/inference.i
Original file line number Diff line number Diff line change
Expand Up @@ -168,7 +168,7 @@ class DotWriter {

std::map<gtsam::Key, gtsam::Vector2> variablePositions;
std::map<char, double> positionHints;
std::set<Key> boxes;
std::set<gtsam::Key> boxes;
std::map<size_t, gtsam::Vector2> factorPositions;
};

Expand Down
10 changes: 5 additions & 5 deletions gtsam/nonlinear/nonlinear.i
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,8 @@ class GraphvizFormatting : gtsam::DotWriter {
GraphvizFormatting();

enum Axis { X, Y, Z, NEGX, NEGY, NEGZ };
Axis paperHorizontalAxis;
Axis paperVerticalAxis;
gtsam::GraphvizFormatting::Axis paperHorizontalAxis;
gtsam::GraphvizFormatting::Axis paperVerticalAxis;

double scale;
bool mergeSimilarFactors;
Expand Down Expand Up @@ -522,13 +522,13 @@ template<PARAMS>
virtual class GncParams {
GncParams(const PARAMS& baseOptimizerParams);
GncParams();
BaseOptimizerParameters baseOptimizerParams;
PARAMS baseOptimizerParams;
gtsam::GncLossType lossType;
size_t maxIterations;
double muStep;
double relativeCostTol;
double weightsTol;
Verbosity verbosity;
gtsam::This::Verbosity verbosity;
gtsam::KeyVector knownInliers;
gtsam::KeyVector knownOutliers;

Expand Down Expand Up @@ -680,7 +680,7 @@ class ISAM2Params {
bool findUnusedFactorSlots;

enum Factorization { CHOLESKY, QR };
Factorization factorization;
gtsam::ISAM2Params::Factorization factorization;
};

class ISAM2Clique {
Expand Down
12 changes: 12 additions & 0 deletions matlab/gtsam_tests/testProperties.m
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
% test property reading and writing
import gtsam.*;

isamParams = ISAM2Params;

isamParams.relinearizeSkip = 123;
EXPECT('isamParams.relinearizeSkip',isamParams.relinearizeSkip==123);

isamParams.enableRelinearization = false;
EXPECT('isamParams.enableRelinearization_false',isamParams.enableRelinearization==false);
isamParams.enableRelinearization = true;
EXPECT('isamParams.enableRelinearization_true',isamParams.enableRelinearization==true);
3 changes: 3 additions & 0 deletions matlab/gtsam_tests/test_gtsam.m
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,9 @@
display 'Starting: testVisualISAMExample'
testVisualISAMExample

display 'Starting: testProperties'
testProperties

%% MATLAB specific
display 'Starting: testUtilities'
testUtilities
Expand Down
26 changes: 26 additions & 0 deletions wrap/DOCS.md
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,32 @@ The python wrapper supports keyword arguments for functions/methods. Hence, the
```

- Class variables are read-write so they can be updated directly in Python.
- For the Matlab wrapper, specifying the full property type (including namespaces) is required.

```cpp
class TriangulationResult {
gtsam::SharedNoiseModel noiseModel;
};
```

- If the property is part of an enum within the class, the type should be specified as `gtsam::Class::Enum`. Similarly for templated types where `This` is used, e.g. `gtsam::This::Enum`.

```cpp
class TriangulationResult {
enum Status { VALID, DEGENERATE, BEHIND_CAMERA, OUTLIER, FAR_POINT };
gtsam::TriangulationResult::Status status;
};

template<PARAMS>
virtual class GncParams {
enum Verbosity {
SILENT,
SUMMARY,
VALUES
};
gtsam::This::Verbosity verbosity;
};
```

- Operator Overloading (Python only)
- You can overload operators just like in C++.
Expand Down
2 changes: 1 addition & 1 deletion wrap/gtwrap/interface_parser/classes.py
Original file line number Diff line number Diff line change
Expand Up @@ -299,7 +299,7 @@ def __init__(
# If the base class is a TemplatedType,
# we want the instantiated Typename
if isinstance(parent_class, TemplatedType):
parent_class = parent_class.typename # type: ignore
pass # Note: this must get handled in InstantiatedClass

self.parent_class = parent_class
else:
Expand Down
Loading