make SharedGaussian inherit SharedNoiseModel
parent
ee6569db29
commit
af9b523b2d
|
|
@ -229,19 +229,19 @@ bool assert_equal(const ConstSubVector& expected, const ConstSubVector& actual,
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
bool linear_dependent(const Vector& vec1, const Vector& vec2, double tol) {
|
bool linear_dependent(const Vector& vec1, const Vector& vec2, double tol) {
|
||||||
if (vec1.size()!=vec2.size()) return false;
|
if (vec1.size()!=vec2.size()) return false;
|
||||||
boost::optional<double> scale;
|
bool flag = false; double scale = 1.0;
|
||||||
size_t m = vec1.size();
|
size_t m = vec1.size();
|
||||||
for(size_t i=0; i<m; i++) {
|
for(size_t i=0; i<m; i++) {
|
||||||
if((fabs(vec1[i])>tol&&fabs(vec2[i])<tol) || (fabs(vec1[i])<tol&&fabs(vec2[i])>tol))
|
if((fabs(vec1[i])>tol&&fabs(vec2[i])<tol) || (fabs(vec1[i])<tol&&fabs(vec2[i])>tol))
|
||||||
return false;
|
return false;
|
||||||
if(vec1[i] == 0 && vec2[i] == 0)
|
if(vec1[i] == 0 && vec2[i] == 0) continue;
|
||||||
continue;
|
if (!flag) {
|
||||||
if (!scale)
|
|
||||||
scale = vec1[i] / vec2[i];
|
scale = vec1[i] / vec2[i];
|
||||||
else if (fabs(vec1[i] - vec2[i] * (*scale)) > tol)
|
flag = true ;
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
return scale.is_initialized();
|
else if (fabs(vec1[i] - vec2[i]*scale) > tol) return false;
|
||||||
|
}
|
||||||
|
return flag;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
|
|
||||||
|
|
@ -19,6 +19,7 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <gtsam/linear/NoiseModel.h>
|
#include <gtsam/linear/NoiseModel.h>
|
||||||
|
#include <gtsam/linear/SharedNoiseModel.h>
|
||||||
|
|
||||||
namespace gtsam { // note, deliberately not in noiseModel namespace
|
namespace gtsam { // note, deliberately not in noiseModel namespace
|
||||||
|
|
||||||
|
|
@ -26,44 +27,32 @@ namespace gtsam { // note, deliberately not in noiseModel namespace
|
||||||
* A useful convenience class to refer to a shared Gaussian model
|
* A useful convenience class to refer to a shared Gaussian model
|
||||||
* Also needed to make noise models in matlab
|
* Also needed to make noise models in matlab
|
||||||
*/
|
*/
|
||||||
struct SharedGaussian: public noiseModel::Gaussian::shared_ptr {
|
struct SharedGaussian: public SharedNoiseModel {
|
||||||
SharedGaussian() {
|
|
||||||
}
|
typedef SharedNoiseModel Base;
|
||||||
// TODO: better way ?
|
|
||||||
SharedGaussian(const noiseModel::Gaussian::shared_ptr& p) :
|
SharedGaussian() {}
|
||||||
noiseModel::Gaussian::shared_ptr(p) {
|
SharedGaussian(const noiseModel::Gaussian::shared_ptr& p) : Base(p) {}
|
||||||
}
|
SharedGaussian(const noiseModel::Diagonal::shared_ptr& p) : Base(p) {}
|
||||||
SharedGaussian(const noiseModel::Diagonal::shared_ptr& p) :
|
SharedGaussian(const noiseModel::Constrained::shared_ptr& p) : Base(p) {}
|
||||||
noiseModel::Gaussian::shared_ptr(p) {
|
SharedGaussian(const noiseModel::Isotropic::shared_ptr& p) : Base(p) {}
|
||||||
}
|
SharedGaussian(const noiseModel::Unit::shared_ptr& p) : Base(p) {}
|
||||||
SharedGaussian(const noiseModel::Constrained::shared_ptr& p) :
|
|
||||||
noiseModel::Gaussian::shared_ptr(p) {
|
|
||||||
}
|
|
||||||
SharedGaussian(const noiseModel::Isotropic::shared_ptr& p) :
|
|
||||||
noiseModel::Gaussian::shared_ptr(p) {
|
|
||||||
}
|
|
||||||
SharedGaussian(const noiseModel::Unit::shared_ptr& p) :
|
|
||||||
noiseModel::Gaussian::shared_ptr(p) {
|
|
||||||
}
|
|
||||||
|
|
||||||
// Define GTSAM_MAGIC_GAUSSIAN to have access to slightly
|
// Define GTSAM_MAGIC_GAUSSIAN to have access to slightly
|
||||||
// dangerous and non-shared (inefficient, wasteful) noise models.
|
// dangerous and non-shared (inefficient, wasteful) noise models.
|
||||||
// Intended to be used only in tests (if you must) and the MATLAB wrapper
|
// Intended to be used only in tests (if you must) and the MATLAB wrapper
|
||||||
#ifdef GTSAM_MAGIC_GAUSSIAN
|
#ifdef GTSAM_MAGIC_GAUSSIAN
|
||||||
SharedGaussian(const Matrix& covariance) :
|
SharedGaussian(const Matrix& covariance)
|
||||||
noiseModel::Gaussian::shared_ptr(noiseModel::Gaussian::Covariance(covariance)) {
|
: Base(noiseModel::Gaussian::Covariance(covariance)) {}
|
||||||
}
|
SharedGaussian(const Vector& sigmas)
|
||||||
SharedGaussian(const Vector& sigmas) :
|
: Base(noiseModel::Diagonal::Sigmas(sigmas)) {}
|
||||||
noiseModel::Gaussian::shared_ptr(noiseModel::Diagonal::Sigmas(sigmas)) {
|
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Define GTSAM_DANGEROUS_GAUSSIAN to have access to bug-prone fixed dimension Gaussians
|
// Define GTSAM_DANGEROUS_GAUSSIAN to have access to bug-prone fixed dimension Gaussians
|
||||||
// Not intended for human use, only for backwards compatibility of old unit tests
|
// Not intended for human use, only for backwards compatibility of old unit tests
|
||||||
#ifdef GTSAM_DANGEROUS_GAUSSIAN
|
#ifdef GTSAM_DANGEROUS_GAUSSIAN
|
||||||
SharedGaussian(const double& s) :
|
SharedGaussian(const double& s) :
|
||||||
noiseModel::Gaussian::shared_ptr(noiseModel::Isotropic::Sigma(
|
Base(noiseModel::Isotropic::Sigma(GTSAM_DANGEROUS_GAUSSIAN, s)) {}
|
||||||
GTSAM_DANGEROUS_GAUSSIAN, s)) {
|
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/** Serialization function */
|
/** Serialization function */
|
||||||
|
|
|
||||||
|
|
@ -12,7 +12,6 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <gtsam/linear/NoiseModel.h>
|
#include <gtsam/linear/NoiseModel.h>
|
||||||
#include <gtsam/linear/SharedGaussian.h>
|
|
||||||
|
|
||||||
namespace gtsam { // note, deliberately not in noiseModel namespace
|
namespace gtsam { // note, deliberately not in noiseModel namespace
|
||||||
|
|
||||||
|
|
@ -21,7 +20,6 @@ namespace gtsam { // note, deliberately not in noiseModel namespace
|
||||||
typedef noiseModel::Base::shared_ptr Base;
|
typedef noiseModel::Base::shared_ptr Base;
|
||||||
|
|
||||||
SharedNoiseModel() {}
|
SharedNoiseModel() {}
|
||||||
SharedNoiseModel(const SharedGaussian &p): Base(p) {}
|
|
||||||
SharedNoiseModel(const noiseModel::Robust::shared_ptr& p): Base(p) {}
|
SharedNoiseModel(const noiseModel::Robust::shared_ptr& p): Base(p) {}
|
||||||
SharedNoiseModel(const noiseModel::Gaussian::shared_ptr& p): Base(p) {}
|
SharedNoiseModel(const noiseModel::Gaussian::shared_ptr& p): Base(p) {}
|
||||||
SharedNoiseModel(const noiseModel::Diagonal::shared_ptr& p): Base(p) {}
|
SharedNoiseModel(const noiseModel::Diagonal::shared_ptr& p): Base(p) {}
|
||||||
|
|
|
||||||
|
|
@ -26,7 +26,7 @@ using namespace boost::assign;
|
||||||
#include <CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
#include <gtsam/base/TestableAssertions.h>
|
#include <gtsam/base/TestableAssertions.h>
|
||||||
#include <gtsam/linear/NoiseModel.h>
|
#include <gtsam/linear/NoiseModel.h>
|
||||||
#include <gtsam/linear/SharedNoiseModel.h>
|
#include <gtsam/linear/SharedGaussian.h>
|
||||||
#include <gtsam/linear/SharedDiagonal.h>
|
#include <gtsam/linear/SharedDiagonal.h>
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
@ -238,8 +238,8 @@ TEST(NoiseModel, QRNan )
|
||||||
TEST(NoiseModel, SmartCovariance )
|
TEST(NoiseModel, SmartCovariance )
|
||||||
{
|
{
|
||||||
bool smart = true;
|
bool smart = true;
|
||||||
SharedNoiseModel expected = Unit::Create(3);
|
SharedGaussian expected = Unit::Create(3);
|
||||||
SharedNoiseModel actual = Gaussian::Covariance(eye(3), smart);
|
SharedGaussian actual = Gaussian::Covariance(eye(3), smart);
|
||||||
EXPECT(assert_equal(*expected,*actual));
|
EXPECT(assert_equal(*expected,*actual));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
@ -247,8 +247,8 @@ TEST(NoiseModel, SmartCovariance )
|
||||||
TEST(NoiseModel, ScalarOrVector )
|
TEST(NoiseModel, ScalarOrVector )
|
||||||
{
|
{
|
||||||
bool smart = true;
|
bool smart = true;
|
||||||
SharedNoiseModel expected = Unit::Create(3);
|
SharedGaussian expected = Unit::Create(3);
|
||||||
SharedNoiseModel actual = Gaussian::Covariance(eye(3), smart);
|
SharedGaussian actual = Gaussian::Covariance(eye(3), smart);
|
||||||
EXPECT(assert_equal(*expected,*actual));
|
EXPECT(assert_equal(*expected,*actual));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue