From 7c07c7080204cf8c8e16c0391ee8d5782b54417b Mon Sep 17 00:00:00 2001 From: Vadim Indelman Date: Thu, 8 Aug 2013 16:08:35 +0000 Subject: [PATCH] Changed Between and Prior Factors and NonLinearEquality back to NoiseModelFactor. --- gtsam.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam.h b/gtsam.h index 65c7ffcaa..c8bb81aae 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2124,7 +2124,7 @@ class NonlinearISAM { #include template -virtual class PriorFactor : gtsam::NonlinearFactor { +virtual class PriorFactor : gtsam::NoiseModelFactor { PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); T prior() const; @@ -2135,7 +2135,7 @@ virtual class PriorFactor : gtsam::NonlinearFactor { #include template -virtual class BetweenFactor : gtsam::NonlinearFactor { +virtual class BetweenFactor : gtsam::NoiseModelFactor { BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel); T measured() const; @@ -2146,7 +2146,7 @@ virtual class BetweenFactor : gtsam::NonlinearFactor { #include template -virtual class NonlinearEquality : gtsam::NonlinearFactor { +virtual class NonlinearEquality : gtsam::NoiseModelFactor { // Constructor - forces exact evaluation NonlinearEquality(size_t j, const T& feasible); // Constructor - allows inexact evaluation