Removed LieScalar from prior factor test and added new test for constructor with Vector3

release/4.3a0
Christian Forster 2014-12-01 10:56:55 -05:00
parent 6b4d2321b4
commit 1f171cf1a1
1 changed files with 10 additions and 4 deletions

View File

@ -5,8 +5,8 @@
* @date Nov 4, 2014 * @date Nov 4, 2014
*/ */
#include <gtsam/base/Vector.h>
#include <gtsam/slam/PriorFactor.h> #include <gtsam/slam/PriorFactor.h>
#include <gtsam/base/LieScalar.h>
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
using namespace std; using namespace std;
@ -14,10 +14,16 @@ using namespace gtsam;
/* ************************************************************************* */ /* ************************************************************************* */
// Constructor // Constructor scalar
TEST(PriorFactor, Constructor) { TEST(PriorFactor, ConstructorScalar) {
SharedNoiseModel model; SharedNoiseModel model;
PriorFactor<LieScalar> factor(1, LieScalar(1.0), model); PriorFactor<double> factor(1, 1.0, model);
}
// Constructor vector3
TEST(PriorFactor, ConstructorVector3) {
SharedNoiseModel model = noiseModel::Isotropic::Sigma(3, 1.0);
PriorFactor<Vector3> factor(1, Vector3(1,2,3), model);
} }
/* ************************************************************************* */ /* ************************************************************************* */