Merge pull request #1649 from borglab/matlab-update

Matlab Wrapper Update
release/4.3a0
Varun Agrawal 2023-10-17 19:20:19 -04:00 committed by GitHub
commit 5ffa7f2e35
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
8 changed files with 45 additions and 6 deletions

View File

@ -64,6 +64,10 @@ set(ignore
gtsam::Point3
gtsam::CustomFactor)
if (APPLE OR WIN32)
list(APPEND ignore gtsam::Symbol)
endif()
set(interface_files
${GTSAM_SOURCE_DIR}/gtsam/gtsam.i
${GTSAM_SOURCE_DIR}/gtsam/base/base.i

View File

@ -10,6 +10,14 @@ The interface generated by the wrap tool also redirects the standard output stre
For instructions on updating the version of the [wrap library](https://github.com/borglab/wrap) included in GTSAM to the latest version, please refer to the [wrap README](https://github.com/borglab/wrap/blob/master/README.md#git-subtree-and-contributing)
### Filename Case Sensitivity
Due to the file name syntax requirements of Matlab, having the files `Symbol.m` (for the class) and `symbol.m` (for the function) together on an OS with a case-insensitive filesystem is impossible.
To put it simply, for an OS like Windows or MacOS where the filesystem is case-insensitive, we cannot have two files `symbol.m` and `Symbol.m` in the same folder. When trying to write one file after another, they will end up overwriting each other. We cannot specify 2 different filenames, since Matlab's syntax prevents that.
For this reason, on Windows and MacOS, we ignore the `Symbol` class and request users to use the `symbol` function exclusively for key creation.
## 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:

View File

@ -12,7 +12,8 @@ Author: Duy Nguyen Ta, Fan Jiang, Matthew Sklar, Varun Agrawal, and Frank Dellae
from typing import Any, Iterable, List, Union
from pyparsing import Optional, ParseResults, delimitedList # type: ignore
from pyparsing import (Literal, Optional, ParseResults, # type: ignore
delimitedList)
from .template import Template
from .tokens import (COMMA, DEFAULT_ARG, EQUAL, IDENT, LOPBRACK, LPAREN, PAIR,
@ -105,8 +106,10 @@ class ReturnType:
The return type can either be a single type or a pair such as <type1, type2>.
"""
# rule to parse optional std:: in front of `pair`
optional_std = Optional(Literal('std::')).suppress()
_pair = (
PAIR.suppress() #
optional_std + PAIR.suppress() #
+ LOPBRACK #
+ Type.rule("type1") #
+ COMMA #

View File

@ -1284,7 +1284,8 @@ class MatlabWrapper(CheckMixin, FormatMixin):
[instantiated_class.name])
else:
# Get the full namespace
class_name = ".".join(instantiated_class.parent.full_namespaces()[1:])
class_name = ".".join(
instantiated_class.parent.full_namespaces()[1:])
if class_name != "":
class_name += '.'
@ -1860,6 +1861,7 @@ class MatlabWrapper(CheckMixin, FormatMixin):
"""
for c in cc_content:
if isinstance(c, list):
# c is a namespace
if len(c) == 0:
continue
@ -1875,6 +1877,7 @@ class MatlabWrapper(CheckMixin, FormatMixin):
self.generate_content(sub_content[1], path_to_folder)
elif isinstance(c[1], list):
# c is a wrapped function
path_to_folder = osp.join(path, c[0])
if not osp.isdir(path_to_folder):
@ -1882,11 +1885,13 @@ class MatlabWrapper(CheckMixin, FormatMixin):
os.makedirs(path_to_folder, exist_ok=True)
except OSError:
pass
for sub_content in c[1]:
path_to_file = osp.join(path_to_folder, sub_content[0])
with open(path_to_file, 'w') as f:
f.write(sub_content[1])
else:
# c is a wrapped class
path_to_file = osp.join(path, c[0])
if not osp.isdir(path_to_file):
@ -1921,6 +1926,8 @@ class MatlabWrapper(CheckMixin, FormatMixin):
for module in modules.values():
# Wrap the full namespace
self.wrap_namespace(module)
# Generate the wrapping code (both C++ and .m files)
self.generate_wrapper(module)
# Generate the corresponding .m and .cpp files

View File

@ -1,6 +1,6 @@
function varargout = TemplatedFunctionRot3(varargin)
if length(varargin) == 1 && isa(varargin{1},'gtsam.Rot3')
functions_wrapper(25, varargin{:});
functions_wrapper(26, varargin{:});
else
error('Arguments do not match any overload of function TemplatedFunctionRot3');
end

View File

@ -229,7 +229,16 @@ void setPose_24(int nargout, mxArray *out[], int nargin, const mxArray *in[])
checkArguments("setPose",nargout,nargin,0);
setPose(gtsam::Pose3());
}
void TemplatedFunctionRot3_25(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void EliminateDiscrete_25(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("EliminateDiscrete",nargout,nargin,2);
gtsam::DiscreteFactorGraph& factors = *unwrap_shared_ptr< gtsam::DiscreteFactorGraph >(in[0], "ptr_gtsamDiscreteFactorGraph");
gtsam::Ordering& frontalKeys = *unwrap_shared_ptr< gtsam::Ordering >(in[1], "ptr_gtsamOrdering");
auto pairResult = EliminateDiscrete(factors,frontalKeys);
out[0] = wrap_shared_ptr(pairResult.first,"gtsam.DiscreteConditional", false);
out[1] = wrap_shared_ptr(pairResult.second,"gtsam.DecisionTreeFactor", false);
}
void TemplatedFunctionRot3_26(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("TemplatedFunctionRot3",nargout,nargin,1);
gtsam::Rot3& t = *unwrap_shared_ptr< gtsam::Rot3 >(in[0], "ptr_gtsamRot3");
@ -323,7 +332,10 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
setPose_24(nargout, out, nargin-1, in+1);
break;
case 25:
TemplatedFunctionRot3_25(nargout, out, nargin-1, in+1);
EliminateDiscrete_25(nargout, out, nargin-1, in+1);
break;
case 26:
TemplatedFunctionRot3_26(nargout, out, nargin-1, in+1);
break;
}
} catch(const std::exception& e) {

View File

@ -30,6 +30,7 @@ PYBIND11_MODULE(functions_py, m_) {
m_.def("DefaultFuncZero",[](int a, int b, double c, int d, bool e){ ::DefaultFuncZero(a, b, c, d, e);}, py::arg("a"), py::arg("b"), py::arg("c") = 0.0, py::arg("d") = 0, py::arg("e") = false);
m_.def("DefaultFuncVector",[](const std::vector<int>& i, const std::vector<string>& s){ ::DefaultFuncVector(i, s);}, py::arg("i") = {1, 2, 3}, py::arg("s") = {"borglab", "gtsam"});
m_.def("setPose",[](const gtsam::Pose3& pose){ ::setPose(pose);}, py::arg("pose") = gtsam::Pose3());
m_.def("EliminateDiscrete",[](const gtsam::DiscreteFactorGraph& factors, const gtsam::Ordering& frontalKeys){return ::EliminateDiscrete(factors, frontalKeys);}, py::arg("factors"), py::arg("frontalKeys"));
m_.def("TemplatedFunctionRot3",[](const gtsam::Rot3& t){ ::TemplatedFunction<gtsam::Rot3>(t);}, py::arg("t"));
#include "python/specializations.h"

View File

@ -36,3 +36,7 @@ void DefaultFuncVector(const std::vector<int> &i = {1, 2, 3}, const std::vector<
// Test for non-trivial default constructor
void setPose(const gtsam::Pose3& pose = gtsam::Pose3());
std::pair<gtsam::DiscreteConditional*, gtsam::DecisionTreeFactor*>
EliminateDiscrete(const gtsam::DiscreteFactorGraph& factors,
const gtsam::Ordering& frontalKeys);