Skip to content

Commit

Permalink
Merge pull request #528 from borglab/fix/wrapper-todos
Browse files Browse the repository at this point in the history
Wrapper fixes
  • Loading branch information
varunagrawal authored Sep 27, 2020
2 parents b9733a8 + 94bb0fb commit b6f095c
Show file tree
Hide file tree
Showing 4 changed files with 24 additions and 123 deletions.
102 changes: 4 additions & 98 deletions gtsam/gtsam.i
Original file line number Diff line number Diff line change
Expand Up @@ -334,99 +334,6 @@ virtual class GenericValue : gtsam::Value {
void serializable() const;
};

#include <gtsam/base/deprecated/LieScalar.h>
class LieScalar {
// Standard constructors
LieScalar();
LieScalar(double d);

// Standard interface
double value() const;

// Testable
void print(string s) const;
bool equals(const gtsam::LieScalar& expected, double tol) const;

// Group
static gtsam::LieScalar identity();
gtsam::LieScalar inverse() const;
gtsam::LieScalar compose(const gtsam::LieScalar& p) const;
gtsam::LieScalar between(const gtsam::LieScalar& l2) const;

// Manifold
size_t dim() const;
gtsam::LieScalar retract(Vector v) const;
Vector localCoordinates(const gtsam::LieScalar& t2) const;

// Lie group
static gtsam::LieScalar Expmap(Vector v);
static Vector Logmap(const gtsam::LieScalar& p);
};

#include <gtsam/base/deprecated/LieVector.h>
class LieVector {
// Standard constructors
LieVector();
LieVector(Vector v);

// Standard interface
Vector vector() const;

// Testable
void print(string s) const;
bool equals(const gtsam::LieVector& expected, double tol) const;

// Group
static gtsam::LieVector identity();
gtsam::LieVector inverse() const;
gtsam::LieVector compose(const gtsam::LieVector& p) const;
gtsam::LieVector between(const gtsam::LieVector& l2) const;

// Manifold
size_t dim() const;
gtsam::LieVector retract(Vector v) const;
Vector localCoordinates(const gtsam::LieVector& t2) const;

// Lie group
static gtsam::LieVector Expmap(Vector v);
static Vector Logmap(const gtsam::LieVector& p);

// enabling serialization functionality
void serialize() const;
};

#include <gtsam/base/deprecated/LieMatrix.h>
class LieMatrix {
// Standard constructors
LieMatrix();
LieMatrix(Matrix v);

// Standard interface
Matrix matrix() const;

// Testable
void print(string s) const;
bool equals(const gtsam::LieMatrix& expected, double tol) const;

// Group
static gtsam::LieMatrix identity();
gtsam::LieMatrix inverse() const;
gtsam::LieMatrix compose(const gtsam::LieMatrix& p) const;
gtsam::LieMatrix between(const gtsam::LieMatrix& l2) const;

// Manifold
size_t dim() const;
gtsam::LieMatrix retract(Vector v) const;
Vector localCoordinates(const gtsam::LieMatrix & t2) const;

// Lie group
static gtsam::LieMatrix Expmap(Vector v);
static Vector Logmap(const gtsam::LieMatrix& p);

// enabling serialization functionality
void serialize() const;
};

//*************************************************************************
// geometry
//*************************************************************************
Expand Down Expand Up @@ -2571,9 +2478,9 @@ class ISAM2 {
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta);
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FactorIndices& removeFactorIndices);
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FactorIndices& removeFactorIndices, const gtsam::KeyGroupMap& constrainedKeys);
// TODO: wrap the full version of update
//void update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, FastMap<Key,int>& constrainedKeys);
//void update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, FastMap<Key,int>& constrainedKeys, bool force_relinearize);
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FactorIndices& removeFactorIndices, gtsam::KeyGroupMap& constrainedKeys, const gtsam::KeyList& noRelinKeys);
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FactorIndices& removeFactorIndices, gtsam::KeyGroupMap& constrainedKeys, const gtsam::KeyList& noRelinKeys, const gtsam::KeyList& extraReelimKeys);
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FactorIndices& removeFactorIndices, gtsam::KeyGroupMap& constrainedKeys, const gtsam::KeyList& noRelinKeys, const gtsam::KeyList& extraReelimKeys, bool force_relinearize);

gtsam::Values getLinearizationPoint() const;
gtsam::Values calculateEstimate() const;
Expand Down Expand Up @@ -2705,8 +2612,7 @@ class BearingRange {
BearingRange(const BEARING& b, const RANGE& r);
BEARING bearing() const;
RANGE range() const;
// TODO(frank): can't class instance itself?
// static gtsam::BearingRange Measure(const POSE& pose, const POINT& point);
static This Measure(const POSE& pose, const POINT& point);
static BEARING MeasureBearing(const POSE& pose, const POINT& point);
static RANGE MeasureRange(const POSE& pose, const POINT& point);
void print(string s) const;
Expand Down
14 changes: 5 additions & 9 deletions gtsam_unstable/gtsam_unstable.i
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,6 @@
// specify the classes from gtsam we are using
virtual class gtsam::Value;
class gtsam::Vector6;
class gtsam::LieScalar;
class gtsam::LieVector;
class gtsam::Point2;
class gtsam::Point2Vector;
class gtsam::Rot2;
Expand Down Expand Up @@ -476,44 +474,42 @@ virtual class DGroundConstraint : gtsam::NonlinearFactor {
DGroundConstraint(size_t key, Vector constraint, const gtsam::noiseModel::Base* model);
};

#include <gtsam/base/deprecated/LieScalar.h>

#include <gtsam_unstable/dynamics/VelocityConstraint3.h>
virtual class VelocityConstraint3 : gtsam::NonlinearFactor {
/** Standard constructor */
VelocityConstraint3(size_t key1, size_t key2, size_t velKey, double dt);

Vector evaluateError(const gtsam::LieScalar& x1, const gtsam::LieScalar& x2, const gtsam::LieScalar& v) const;
Vector evaluateError(const double& x1, const double& x2, const double& v) const;
};

#include <gtsam_unstable/dynamics/Pendulum.h>
virtual class PendulumFactor1 : gtsam::NonlinearFactor {
/** Standard constructor */
PendulumFactor1(size_t k1, size_t k, size_t velKey, double dt);

Vector evaluateError(const gtsam::LieScalar& qk1, const gtsam::LieScalar& qk, const gtsam::LieScalar& v) const;
Vector evaluateError(const double& qk1, const double& qk, const double& v) const;
};

#include <gtsam_unstable/dynamics/Pendulum.h>
virtual class PendulumFactor2 : gtsam::NonlinearFactor {
/** Standard constructor */
PendulumFactor2(size_t vk1, size_t vk, size_t qKey, double dt, double L, double g);

Vector evaluateError(const gtsam::LieScalar& vk1, const gtsam::LieScalar& vk, const gtsam::LieScalar& q) const;
Vector evaluateError(const double& vk1, const double& vk, const double& q) const;
};

virtual class PendulumFactorPk : gtsam::NonlinearFactor {
/** Standard constructor */
PendulumFactorPk(size_t pk, size_t qk, size_t qk1, double h, double m, double r, double g, double alpha);

Vector evaluateError(const gtsam::LieScalar& pk, const gtsam::LieScalar& qk, const gtsam::LieScalar& qk1) const;
Vector evaluateError(const double& pk, const double& qk, const double& qk1) const;
};

virtual class PendulumFactorPk1 : gtsam::NonlinearFactor {
/** Standard constructor */
PendulumFactorPk1(size_t pk1, size_t qk, size_t qk1, double h, double m, double r, double g, double alpha);

Vector evaluateError(const gtsam::LieScalar& pk1, const gtsam::LieScalar& qk, const gtsam::LieScalar& qk1) const;
Vector evaluateError(const double& pk1, const double& qk, const double& qk1) const;
};

#include <gtsam_unstable/dynamics/SimpleHelicopter.h>
Expand Down
27 changes: 15 additions & 12 deletions matlab/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,16 @@ http://borg.cc.gatech.edu/projects/gtsam

This is the GTSAM MATLAB toolbox, a MATLAB wrapper around the GTSAM C++ library. To build it, enable `GTSAM_INSTALL_MATLAB_TOOLBOX=ON` in CMake.

The interface to the toolbox is generated automatically by the wrap
tool which directly parses C++ header files. The tool generates matlab proxy objects together with all the native functions for wrapping and unwrapping scalar and non scalar types and objects. The interface generated by the wrap tool also redirects the standard output stream (cout) to matlab's console.
The interface to the toolbox is generated automatically by the wrap tool which directly parses C++ header files.
The tool generates matlab proxy objects together with all the native functions for wrapping and unwrapping scalar and non scalar types and objects.
The interface generated by the wrap tool also redirects the standard output stream (cout) to matlab's console.

## Ubuntu

If you have a newer Ubuntu system (later than 10.04), you must make a small modification to your MATLAB installation, due to MATLAB being distributed with an old version of the C++ standard library. Delete or rename all files starting with `libstdc++` in your MATLAB installation directory, in paths:

/usr/local/MATLAB/[version]/sys/os/[system]/
/usr/local/MATLAB/[version]/bin/[system]/
If you have a newer Ubuntu system (later than 10.04), you must make a small modification to your MATLAB installation, due to MATLAB being distributed with an old version of the C++ standard library. Delete or rename all files starting with `libstdc++` in your MATLAB installation directory, in paths:

/usr/local/MATLAB/[version]/sys/os/[system]/
/usr/local/MATLAB/[version]/bin/[system]/

## Adding the toolbox to your MATLAB path

Expand All @@ -37,25 +37,28 @@ export LD_LIBRARY_PATH=<install-path>/gtsam:$LD_LIBRARY_PATH

### Linker issues

If you compile the MATLAB toolbox and everything compiles smoothly, but when you run any MATLAB script, you get following error messages in MATLAB
If you compile the MATLAB toolbox and everything compiles smoothly, but when you run any MATLAB script, you get any of the following error messages in MATLAB

```
Invalid MEX-file '/usr/local/gtsam_toolbox/gtsam_wrapper.mexa64':
Missing symbol 'mexAtExit' required by '/usr/local/gtsam_toolbox/gtsam_wrapper.mexa64'
Missing symbol 'mexCallMATLABWithObject' required by '/usr/local/gtsam_toolbox/gtsam_wrapper.mexa64'
...
```

run following shell line

```sh
export LD_PRELOAD=/usr/lib/x86_64-linux-gnu/libstdc++.so.6
```
before you run MATLAB from the same shell.

This mainly happens if you have GCC >= 5 and newer version MATLAB like R2017a.
before you run MATLAB from the same shell.

This mainly happens if you have GCC >= 5 and newer version MATLAB like R2017a.

## Trying out the examples

The examples are located in the 'gtsam_examples' subfolder. You may either run them individually at the MATLAB command line, or open the GTSAM example GUI by running 'gtsamExamples'. Example:
The examples are located in the 'gtsam_examples' subfolder. You may either run them individually at the MATLAB command line, or open the GTSAM example GUI by running 'gtsamExamples'. Example:

```matlab
>> cd /Users/yourname/toolbox % Change to wherever you installed the toolbox
Expand All @@ -65,7 +68,7 @@ The examples are located in the 'gtsam_examples' subfolder. You may either run

## Running the unit tests

The GTSAM MATLAB toolbox also has a small set of unit tests located in the gtsam_tests directory. Example:
The GTSAM MATLAB toolbox also has a small set of unit tests located in the gtsam_tests directory. Example:

```matlab
>> cd /Users/yourname/toolbox % Change to wherever you installed the toolbox
Expand All @@ -86,4 +89,4 @@ Tests complete!

## Writing your own code

Coding for the GTSAM MATLAB toolbox is straightforward and very fast once you understand a few basic concepts! Please see the manual to get started.
Coding for the GTSAM MATLAB toolbox is straightforward and very fast once you understand a few basic concepts! Please see the manual to get started.
4 changes: 0 additions & 4 deletions matlab/gtsam_tests/testSerialization.m
Original file line number Diff line number Diff line change
Expand Up @@ -28,10 +28,6 @@
pose1ds = Pose2.string_deserialize(serialized_pose1);
CHECK('pose1ds.equals(pose1, 1e-9)', pose1ds.equals(pose1, 1e-9));

serialized_landmark1 = landmark1.string_serialize();
landmark1ds = Point2.string_deserialize(serialized_landmark1);
CHECK('landmark1ds.equals(landmark1, 1e-9)', landmark1ds.equals(landmark1, 1e-9));

%% Create and serialize Values
values = Values;
values.insert(i1, pose1);
Expand Down

0 comments on commit b6f095c

Please sign in to comment.