Fixes to get matlab wrapper working properly

release/4.3a0
Varun Agrawal 2022-02-01 19:08:46 -05:00
parent ad0d7e4b21
commit 134e82836e
4 changed files with 7 additions and 8 deletions

View File

@ -97,7 +97,7 @@ virtual class DiscreteConditional : gtsam::DecisionTreeFactor {
const gtsam::Ordering& orderedKeys);
gtsam::DiscreteConditional operator*(
const gtsam::DiscreteConditional& other) const;
DiscreteConditional marginal(gtsam::Key key) const;
gtsam::DiscreteConditional marginal(gtsam::Key key) const;
void print(string s = "Discrete Conditional\n",
const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;

View File

@ -223,12 +223,12 @@ enum KernelFunctionType {
KernelFunctionTypeTUKEY
};
std::pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load2D(
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load2D(
string filename, gtsam::noiseModel::Diagonal* model = nullptr,
size_t maxIndex = 0, bool addNoise = false, bool smart = true,
gtsam::NoiseFormat noiseFormat = gtsam::NoiseFormatAUTO,
gtsam::NoiseFormat noiseFormat = gtsam::NoiseFormat::NoiseFormatAUTO,
gtsam::KernelFunctionType kernelFunctionType =
gtsam::KernelFunctionTypeNONE);
gtsam::KernelFunctionType::KernelFunctionTypeNONE);
void save2D(const gtsam::NonlinearFactorGraph& graph,
const gtsam::Values& config, gtsam::noiseModel::Diagonal* model,
@ -259,7 +259,7 @@ pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load3D(string filename);
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> readG2o(
string filename, const bool is3D = false,
gtsam::KernelFunctionType kernelFunctionType =
gtsam::KernelFunctionTypeNONE);
gtsam::KernelFunctionType::KernelFunctionTypeNONE);
void writeG2o(const gtsam::NonlinearFactorGraph& graph,
const gtsam::Values& estimate, string filename);

View File

@ -68,6 +68,8 @@ set(interface_files
${GTSAM_SOURCE_DIR}/gtsam/gtsam.i
${GTSAM_SOURCE_DIR}/gtsam/base/base.i
${GTSAM_SOURCE_DIR}/gtsam/basis/basis.i
${PROJECT_SOURCE_DIR}/gtsam/inference/inference.i
# ${PROJECT_SOURCE_DIR}/gtsam/discrete/discrete.i #TODO Matlab wrapper has a bug for raw pointers
${GTSAM_SOURCE_DIR}/gtsam/geometry/geometry.i
${GTSAM_SOURCE_DIR}/gtsam/linear/linear.i
${GTSAM_SOURCE_DIR}/gtsam/nonlinear/nonlinear.i

View File

@ -10,6 +10,3 @@
* Without this they will be automatically converted to a Python object, and all
* mutations on Python side will not be reflected on C++.
*/
#include <pybind11/stl.h>