Added marginals in MATLAB, but had to fix a bug in converting from 64 bit ints to size_t. This begs the question what happens on 32-bit machines with Symbols.
parent
382e3311fd
commit
8a69bb8bcb
|
@ -64,7 +64,7 @@ int main(int argc, char** argv) {
|
||||||
result.print("\nFinal result:\n ");
|
result.print("\nFinal result:\n ");
|
||||||
|
|
||||||
// Query the marginals
|
// Query the marginals
|
||||||
Marginals marginals(graph, result);
|
Marginals marginals = graph.marginals(result);
|
||||||
cout.precision(2);
|
cout.precision(2);
|
||||||
cout << "\nP1:\n" << marginals.marginalCovariance(pose2SLAM::PoseKey(1)) << endl;
|
cout << "\nP1:\n" << marginals.marginalCovariance(pose2SLAM::PoseKey(1)) << endl;
|
||||||
cout << "\nP2:\n" << marginals.marginalCovariance(pose2SLAM::PoseKey(2)) << endl;
|
cout << "\nP2:\n" << marginals.marginalCovariance(pose2SLAM::PoseKey(2)) << endl;
|
||||||
|
|
|
@ -43,8 +43,8 @@ initialEstimate.print(sprintf('\nInitial estimate:\n '));
|
||||||
result = graph.optimize(initialEstimate);
|
result = graph.optimize(initialEstimate);
|
||||||
result.print(sprintf('\nFinal result:\n '));
|
result.print(sprintf('\nFinal result:\n '));
|
||||||
|
|
||||||
%% Use an explicit Optimizer object so we can query the marginals
|
%% Query the marginals
|
||||||
% marginals = gtsamMarginals(graph, result);
|
marginals = graph.marginals(result);
|
||||||
% marginals.marginalCovariance(pose2SLAMPoseKey(1))
|
x1=gtsamSymbol('x',1); marginals.marginalCovariance(x1.key)
|
||||||
% marginals.marginalCovariance(pose2SLAMPoseKey(2))
|
x2=gtsamSymbol('x',2); marginals.marginalCovariance(x2.key)
|
||||||
% marginals.marginalCovariance(pose2SLAMPoseKey(3))
|
x3=gtsamSymbol('x',3); marginals.marginalCovariance(x3.key)
|
||||||
|
|
38
gtsam.h
38
gtsam.h
|
@ -347,13 +347,14 @@ class GaussianFactorGraph {
|
||||||
|
|
||||||
// Building the graph
|
// Building the graph
|
||||||
void add(gtsam::JacobianFactor* factor);
|
void add(gtsam::JacobianFactor* factor);
|
||||||
void add(Vector b);
|
// all these won't work as MATLAB can't handle overloading
|
||||||
void add(int key1, Matrix A1, Vector b, const gtsam::SharedDiagonal& model);
|
// void add(Vector b);
|
||||||
void add(int key1, Matrix A1, int key2, Matrix A2, Vector b,
|
// void add(int key1, Matrix A1, Vector b, const gtsam::SharedDiagonal& model);
|
||||||
const gtsam::SharedDiagonal& model);
|
// void add(int key1, Matrix A1, int key2, Matrix A2, Vector b,
|
||||||
void add(int key1, Matrix A1, int key2, Matrix A2, int key3, Matrix A3,
|
// const gtsam::SharedDiagonal& model);
|
||||||
Vector b, const gtsam::SharedDiagonal& model);
|
// void add(int key1, Matrix A1, int key2, Matrix A2, int key3, Matrix A3,
|
||||||
void add(gtsam::HessianFactor* factor);
|
// Vector b, const gtsam::SharedDiagonal& model);
|
||||||
|
// void add(gtsam::HessianFactor* factor);
|
||||||
|
|
||||||
// error and probability
|
// error and probability
|
||||||
double error(const gtsam::VectorValues& c) const;
|
double error(const gtsam::VectorValues& c) const;
|
||||||
|
@ -380,7 +381,7 @@ class GaussianSequentialSolver {
|
||||||
|
|
||||||
class KalmanFilter {
|
class KalmanFilter {
|
||||||
KalmanFilter(size_t n);
|
KalmanFilter(size_t n);
|
||||||
gtsam::GaussianDensity* init(Vector x0, const gtsam::SharedDiagonal& P0);
|
// gtsam::GaussianDensity* init(Vector x0, const gtsam::SharedDiagonal& P0);
|
||||||
gtsam::GaussianDensity* init(Vector x0, Matrix P0);
|
gtsam::GaussianDensity* init(Vector x0, Matrix P0);
|
||||||
void print(string s) const;
|
void print(string s) const;
|
||||||
static int step(gtsam::GaussianDensity* p);
|
static int step(gtsam::GaussianDensity* p);
|
||||||
|
@ -400,6 +401,12 @@ class KalmanFilter {
|
||||||
// nonlinear
|
// nonlinear
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
|
|
||||||
|
class Symbol {
|
||||||
|
Symbol(char c, size_t j);
|
||||||
|
void print(string s) const;
|
||||||
|
size_t key() const;
|
||||||
|
};
|
||||||
|
|
||||||
class Ordering {
|
class Ordering {
|
||||||
Ordering();
|
Ordering();
|
||||||
void print(string s) const;
|
void print(string s) const;
|
||||||
|
@ -407,20 +414,21 @@ class Ordering {
|
||||||
void push_back(size_t key);
|
void push_back(size_t key);
|
||||||
};
|
};
|
||||||
|
|
||||||
//Andrew says: Required definitions for Marginal arguments
|
|
||||||
class NonlinearFactorGraph {
|
class NonlinearFactorGraph {
|
||||||
NonlinearFactorGraph();
|
NonlinearFactorGraph();
|
||||||
//This need to be populated with whatever functions might be needed.
|
|
||||||
};
|
};
|
||||||
|
|
||||||
class Values {
|
class Values {
|
||||||
Values();
|
Values();
|
||||||
//Same here
|
void print(string s) const;
|
||||||
|
bool exists(size_t j) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
// Frank says: this does not work. Why not?
|
|
||||||
class Marginals {
|
class Marginals {
|
||||||
Marginals(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& solution);
|
Marginals(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& solution);
|
||||||
|
void print(string s) const;
|
||||||
|
Matrix marginalCovariance(size_t variable) const;
|
||||||
|
Matrix marginalInformation(size_t variable) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
}///\namespace gtsam
|
}///\namespace gtsam
|
||||||
|
@ -471,7 +479,7 @@ class Odometry {
|
||||||
}///\namespace planarSLAM
|
}///\namespace planarSLAM
|
||||||
|
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
// gtsam::Pose2SLAM
|
// Pose2SLAM
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
|
|
||||||
#include <gtsam/slam/pose2SLAM.h>
|
#include <gtsam/slam/pose2SLAM.h>
|
||||||
|
@ -481,6 +489,7 @@ class Values {
|
||||||
Values();
|
Values();
|
||||||
void print(string s) const;
|
void print(string s) const;
|
||||||
void insertPose(int key, const gtsam::Pose2& pose);
|
void insertPose(int key, const gtsam::Pose2& pose);
|
||||||
|
gtsam::Symbol poseKey(int i);
|
||||||
gtsam::Pose2 pose(int i);
|
gtsam::Pose2 pose(int i);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -497,7 +506,8 @@ class Graph {
|
||||||
void addPrior(int key, const gtsam::Pose2& pose, const gtsam::SharedNoiseModel& noiseModel);
|
void addPrior(int key, const gtsam::Pose2& pose, const gtsam::SharedNoiseModel& noiseModel);
|
||||||
void addPoseConstraint(int key, const gtsam::Pose2& pose);
|
void addPoseConstraint(int key, const gtsam::Pose2& pose);
|
||||||
void addOdometry(int key1, int key2, const gtsam::Pose2& odometry, const gtsam::SharedNoiseModel& noiseModel);
|
void addOdometry(int key1, int key2, const gtsam::Pose2& odometry, const gtsam::SharedNoiseModel& noiseModel);
|
||||||
pose2SLAM::Values optimize(const pose2SLAM::Values& initialEstimate);
|
pose2SLAM::Values optimize(const pose2SLAM::Values& initialEstimate) const;
|
||||||
|
gtsam::Marginals marginals(const pose2SLAM::Values& solution) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
}///\namespace pose2SLAM
|
}///\namespace pose2SLAM
|
||||||
|
|
|
@ -206,39 +206,53 @@ string unwrap<string>(const mxArray* array) {
|
||||||
return str;
|
return str;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Check for 64-bit, as Mathworks says mxGetScalar only good for 32 bit
|
||||||
|
template <typename T>
|
||||||
|
T myGetScalar(const mxArray* array) {
|
||||||
|
switch (mxGetClassID(array)) {
|
||||||
|
case mxINT64_CLASS:
|
||||||
|
return (T) *(int64_t*) mxGetData(array);
|
||||||
|
case mxUINT64_CLASS:
|
||||||
|
return (T) *(uint64_t*) mxGetData(array);
|
||||||
|
default:
|
||||||
|
// hope for the best!
|
||||||
|
return (T) mxGetScalar(array);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// specialization to bool
|
// specialization to bool
|
||||||
template<>
|
template<>
|
||||||
bool unwrap<bool>(const mxArray* array) {
|
bool unwrap<bool>(const mxArray* array) {
|
||||||
checkScalar(array,"unwrap<bool>");
|
checkScalar(array,"unwrap<bool>");
|
||||||
return mxGetScalar(array) != 0.0;
|
return myGetScalar<bool>(array);
|
||||||
}
|
}
|
||||||
|
|
||||||
// specialization to bool
|
// specialization to bool
|
||||||
template<>
|
template<>
|
||||||
char unwrap<char>(const mxArray* array) {
|
char unwrap<char>(const mxArray* array) {
|
||||||
checkScalar(array,"unwrap<char>");
|
checkScalar(array,"unwrap<char>");
|
||||||
return (char)mxGetScalar(array);
|
return myGetScalar<char>(array);
|
||||||
}
|
|
||||||
|
|
||||||
// specialization to size_t
|
|
||||||
template<>
|
|
||||||
size_t unwrap<size_t>(const mxArray* array) {
|
|
||||||
checkScalar(array,"unwrap<size_t>");
|
|
||||||
return (size_t)mxGetScalar(array);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// specialization to int
|
// specialization to int
|
||||||
template<>
|
template<>
|
||||||
int unwrap<int>(const mxArray* array) {
|
int unwrap<int>(const mxArray* array) {
|
||||||
checkScalar(array,"unwrap<int>");
|
checkScalar(array,"unwrap<int>");
|
||||||
return (int)mxGetScalar(array);
|
return myGetScalar<int>(array);
|
||||||
|
}
|
||||||
|
|
||||||
|
// specialization to size_t
|
||||||
|
template<>
|
||||||
|
size_t unwrap<size_t>(const mxArray* array) {
|
||||||
|
checkScalar(array, "unwrap<size_t>");
|
||||||
|
return myGetScalar<size_t>(array);
|
||||||
}
|
}
|
||||||
|
|
||||||
// specialization to double
|
// specialization to double
|
||||||
template<>
|
template<>
|
||||||
double unwrap<double>(const mxArray* array) {
|
double unwrap<double>(const mxArray* array) {
|
||||||
checkScalar(array,"unwrap<double>");
|
checkScalar(array,"unwrap<double>");
|
||||||
return (double)mxGetScalar(array);
|
return myGetScalar<double>(array);
|
||||||
}
|
}
|
||||||
|
|
||||||
// specialization to Eigen vector
|
// specialization to Eigen vector
|
||||||
|
|
Loading…
Reference in New Issue