Merging 'master' into 'wrap'

release/4.3a0
Varun Agrawal 2022-10-28 22:43:46 -04:00
commit 1999078177
6 changed files with 83 additions and 5 deletions

View File

@ -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++.

View File

@ -1181,7 +1181,7 @@ class MatlabWrapper(CheckMixin, FormatMixin):
def wrap_collector_function_return_types(self, return_type, func_id):
"""
Wrap the return type of the collector function.
Wrap the return type of the collector function when a std::pair is returned.
"""
return_type_text = ' out[' + str(func_id) + '] = '
pair_value = 'first' if func_id == 0 else 'second'
@ -1239,10 +1239,10 @@ class MatlabWrapper(CheckMixin, FormatMixin):
if ctype.typename.name not in self.ignore_namespace:
expanded += textwrap.indent(
'out[0] = wrap_shared_ptr({}, false);'.format(shared_obj),
'out[0] = wrap_shared_ptr({0}, false);'.format(shared_obj),
prefix=' ')
else:
expanded += ' out[0] = wrap< {} >({});'.format(
expanded += ' out[0] = wrap< {0} >({1});'.format(
ctype.typename.name, obj)
return expanded

View File

@ -1,9 +1,13 @@
%class GeneralSFMFactorCal3Bundler, see Doxygen page for details
%at https://gtsam.org/doxygen/
%
%-------Properties-------
%verbosity
%
classdef GeneralSFMFactorCal3Bundler < handle
properties
ptr_gtsamGeneralSFMFactorCal3Bundler = 0
verbosity
end
methods
function obj = GeneralSFMFactorCal3Bundler(varargin)
@ -24,6 +28,16 @@ classdef GeneralSFMFactorCal3Bundler < handle
%DISPLAY Calls print on the object
function disp(obj), obj.display; end
%DISP Calls print on the object
function varargout = get.verbosity(this)
varargout{1} = special_cases_wrapper(11, this);
this.verbosity = varargout{1};
end
function set.verbosity(this, value)
obj.verbosity = value;
special_cases_wrapper(12, this, value);
end
end
methods(Static = true)

View File

@ -204,6 +204,21 @@ void gtsamGeneralSFMFactorCal3Bundler_deconstructor_10(int nargout, mxArray *out
delete self;
}
void gtsamGeneralSFMFactorCal3Bundler_get_verbosity_11(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("verbosity",nargout,nargin-1,0);
auto obj = unwrap_shared_ptr<gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3>>(in[0], "ptr_gtsamGeneralSFMFactorCal3Bundler");
out[0] = wrap_shared_ptr(boost::make_shared<gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3>::Verbosity>(obj->verbosity),"gtsam.GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3>.Verbosity", false);
}
void gtsamGeneralSFMFactorCal3Bundler_set_verbosity_12(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("verbosity",nargout,nargin-1,1);
auto obj = unwrap_shared_ptr<gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3>>(in[0], "ptr_gtsamGeneralSFMFactorCal3Bundler");
boost::shared_ptr<gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3>::Verbosity> verbosity = unwrap_shared_ptr< gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3>::Verbosity >(in[1], "ptr_gtsamGeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3>Verbosity");
obj->verbosity = *verbosity;
}
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
@ -249,6 +264,12 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
case 10:
gtsamGeneralSFMFactorCal3Bundler_deconstructor_10(nargout, out, nargin-1, in+1);
break;
case 11:
gtsamGeneralSFMFactorCal3Bundler_get_verbosity_11(nargout, out, nargin-1, in+1);
break;
case 12:
gtsamGeneralSFMFactorCal3Bundler_set_verbosity_12(nargout, out, nargin-1, in+1);
break;
}
} catch(const std::exception& e) {
mexErrMsgTxt(("Exception from gtsam:\n" + std::string(e.what()) + "\n").c_str());

View File

@ -32,7 +32,15 @@ PYBIND11_MODULE(special_cases_py, m_) {
py::class_<gtsam::PinholeCamera<gtsam::Cal3Bundler>, std::shared_ptr<gtsam::PinholeCamera<gtsam::Cal3Bundler>>>(m_gtsam, "PinholeCameraCal3Bundler");
py::class_<gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3>, std::shared_ptr<gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3>>>(m_gtsam, "GeneralSFMFactorCal3Bundler");
py::class_<gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3>, std::shared_ptr<gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3>>> generalsfmfactorcal3bundler(m_gtsam, "GeneralSFMFactorCal3Bundler");
generalsfmfactorcal3bundler
.def_readwrite("verbosity", &gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3>::verbosity);
py::enum_<gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3>::Verbosity>(generalsfmfactorcal3bundler, "Verbosity", py::arithmetic())
.value("SILENT", gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3>::Verbosity::SILENT)
.value("SUMMARY", gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3>::Verbosity::SUMMARY)
.value("VALUES", gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3>::Verbosity::VALUES);
#include "python/specializations.h"

View File

@ -17,7 +17,16 @@ class NonlinearFactorGraph {
// Typedef with template as template arg.
template<CALIBRATION, POINT>
class GeneralSFMFactor {};
class GeneralSFMFactor {
gtsam::This::Verbosity verbosity;
enum Verbosity {
SILENT,
SUMMARY,
VALUES
};
};
typedef gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3> GeneralSFMFactorCal3Bundler;
// Template as template arg for class property.