Removed extraneous "shared" prefix from SharedNoiseModel named constructors

release/4.3a0
Alex Cunningham 2012-02-12 17:41:57 +00:00
parent d0e9b1d51a
commit 5a3740daeb
5 changed files with 22 additions and 22 deletions

View File

@ -28,20 +28,20 @@ graph = planarSLAMGraph;
%% Add prior %% Add prior
% gaussian for prior % gaussian for prior
prior_model = gtsamSharedNoiseModel_sharedSigmas([0.3; 0.3; 0.1]); prior_model = gtsamSharedNoiseModel_Sigmas([0.3; 0.3; 0.1]);
prior_measurement = gtsamPose2(0.0, 0.0, 0.0); % prior at origin prior_measurement = gtsamPose2(0.0, 0.0, 0.0); % prior at origin
graph.addPrior(x1, prior_measurement, prior_model); % add directly to graph graph.addPrior(x1, prior_measurement, prior_model); % add directly to graph
%% Add odometry %% Add odometry
% general noisemodel for odometry % general noisemodel for odometry
odom_model = gtsamSharedNoiseModel_sharedSigmas([0.2; 0.2; 0.1]); odom_model = gtsamSharedNoiseModel_Sigmas([0.2; 0.2; 0.1]);
odom_measurement = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case) odom_measurement = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case)
graph.addOdometry(x1, x2, odom_measurement, odom_model); graph.addOdometry(x1, x2, odom_measurement, odom_model);
graph.addOdometry(x2, x3, odom_measurement, odom_model); graph.addOdometry(x2, x3, odom_measurement, odom_model);
%% Add measurements %% Add measurements
% general noisemodel for measurements % general noisemodel for measurements
meas_model = gtsamSharedNoiseModel_sharedSigmas([0.1; 0.2]); meas_model = gtsamSharedNoiseModel_Sigmas([0.1; 0.2]);
% create the measurement values - indices are (pose id, landmark id) % create the measurement values - indices are (pose id, landmark id)
degrees = pi/180; degrees = pi/180;

View File

@ -28,20 +28,20 @@ graph = pose2SLAMGraph;
%% Add prior %% Add prior
% gaussian for prior % gaussian for prior
prior_model = gtsamSharedNoiseModel_sharedSigmas([0.3; 0.3; 0.1]); prior_model = gtsamSharedNoiseModel_Sigmas([0.3; 0.3; 0.1]);
prior_measurement = gtsamPose2(0.0, 0.0, 0.0); % prior at origin prior_measurement = gtsamPose2(0.0, 0.0, 0.0); % prior at origin
graph.addPrior(x1, prior_measurement, prior_model); % add directly to graph graph.addPrior(x1, prior_measurement, prior_model); % add directly to graph
%% Add odometry %% Add odometry
% general noisemodel for odometry % general noisemodel for odometry
odom_model = gtsamSharedNoiseModel_sharedSigmas([0.2; 0.2; 0.1]); odom_model = gtsamSharedNoiseModel_Sigmas([0.2; 0.2; 0.1]);
odom_measurement = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case) odom_measurement = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case)
graph.addOdometry(x1, x2, odom_measurement, odom_model); graph.addOdometry(x1, x2, odom_measurement, odom_model);
graph.addOdometry(x2, x3, odom_measurement, odom_model); graph.addOdometry(x2, x3, odom_measurement, odom_model);
%% Add measurements %% Add measurements
% general noisemodel for measurements % general noisemodel for measurements
meas_model = gtsamSharedNoiseModel_sharedSigmas([0.1; 0.2]); meas_model = gtsamSharedNoiseModel_Sigmas([0.1; 0.2]);
% print % print
graph.print('full graph'); graph.print('full graph');

View File

@ -26,13 +26,13 @@ graph = pose2SLAMGraph;
%% Add prior %% Add prior
% gaussian for prior % gaussian for prior
prior_model = gtsamSharedNoiseModel_sharedSigmas([0.3; 0.3; 0.1]); prior_model = gtsamSharedNoiseModel_Sigmas([0.3; 0.3; 0.1]);
prior_measurement = gtsamPose2(0.0, 0.0, 0.0); % prior at origin prior_measurement = gtsamPose2(0.0, 0.0, 0.0); % prior at origin
graph.addPrior(x1, prior_measurement, prior_model); % add directly to graph graph.addPrior(x1, prior_measurement, prior_model); % add directly to graph
%% Add odometry %% Add odometry
% general noisemodel for odometry % general noisemodel for odometry
odom_model = gtsamSharedNoiseModel_sharedSigmas([0.2; 0.2; 0.1]); odom_model = gtsamSharedNoiseModel_Sigmas([0.2; 0.2; 0.1]);
odom_measurement = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case) odom_measurement = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case)
graph.addOdometry(x1, x2, odom_measurement, odom_model); graph.addOdometry(x1, x2, odom_measurement, odom_model);
graph.addOdometry(x2, x3, odom_measurement, odom_model); graph.addOdometry(x2, x3, odom_measurement, odom_model);

14
gtsam.h
View File

@ -229,13 +229,13 @@ class SharedDiagonal {
}; };
class SharedNoiseModel { class SharedNoiseModel {
static gtsam::SharedNoiseModel sharedSigmas(Vector sigmas); static gtsam::SharedNoiseModel Sigmas(Vector sigmas);
static gtsam::SharedNoiseModel sharedSigma(size_t dim, double sigma); static gtsam::SharedNoiseModel Sigma(size_t dim, double sigma);
static gtsam::SharedNoiseModel sharedPrecisions(Vector precisions); static gtsam::SharedNoiseModel Precisions(Vector precisions);
static gtsam::SharedNoiseModel sharedPrecision(size_t dim, double precision); static gtsam::SharedNoiseModel Precision(size_t dim, double precision);
static gtsam::SharedNoiseModel sharedUnit(size_t dim); static gtsam::SharedNoiseModel Unit(size_t dim);
static gtsam::SharedNoiseModel sharedSqrtInformation(Matrix R); static gtsam::SharedNoiseModel SqrtInformation(Matrix R);
static gtsam::SharedNoiseModel sharedCovariance(Matrix covariance); static gtsam::SharedNoiseModel Covariance(Matrix covariance);
void print(string s) const; void print(string s) const;
}; };

View File

@ -50,31 +50,31 @@ namespace gtsam { // note, deliberately not in noiseModel namespace
// Static syntactic sugar functions to create noisemodels directly // Static syntactic sugar functions to create noisemodels directly
// These should only be used with the Matlab interface // These should only be used with the Matlab interface
static inline SharedNoiseModel sharedSigmas(const Vector& sigmas, bool smart=false) { static inline SharedNoiseModel Sigmas(const Vector& sigmas, bool smart=false) {
return noiseModel::Diagonal::Sigmas(sigmas, smart); return noiseModel::Diagonal::Sigmas(sigmas, smart);
} }
static inline SharedNoiseModel sharedSigma(size_t dim, double sigma) { static inline SharedNoiseModel Sigma(size_t dim, double sigma) {
return noiseModel::Isotropic::Sigma(dim, sigma); return noiseModel::Isotropic::Sigma(dim, sigma);
} }
static inline SharedNoiseModel sharedPrecisions(const Vector& precisions) { static inline SharedNoiseModel Precisions(const Vector& precisions) {
return noiseModel::Diagonal::Precisions(precisions); return noiseModel::Diagonal::Precisions(precisions);
} }
static inline SharedNoiseModel sharedPrecision(size_t dim, double precision) { static inline SharedNoiseModel Precision(size_t dim, double precision) {
return noiseModel::Isotropic::Precision(dim, precision); return noiseModel::Isotropic::Precision(dim, precision);
} }
static inline SharedNoiseModel sharedUnit(size_t dim) { static inline SharedNoiseModel Unit(size_t dim) {
return noiseModel::Unit::Create(dim); return noiseModel::Unit::Create(dim);
} }
static inline SharedNoiseModel sharedSqrtInformation(const Matrix& R) { static inline SharedNoiseModel SqrtInformation(const Matrix& R) {
return noiseModel::Gaussian::SqrtInformation(R); return noiseModel::Gaussian::SqrtInformation(R);
} }
static inline SharedNoiseModel sharedCovariance(const Matrix& covariance, bool smart=false) { static inline SharedNoiseModel Covariance(const Matrix& covariance, bool smart=false) {
return noiseModel::Gaussian::Covariance(covariance, smart); return noiseModel::Gaussian::Covariance(covariance, smart);
} }