testSampler.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
20 
21 #include <gtsam/linear/Sampler.h>
22 
23 using namespace gtsam;
24 
25 const double tol = 1e-5;
26 
27 static const Vector3 kSigmas(1.0, 0.1, 0.0);
28 
29 /* ************************************************************************* */
30 TEST(testSampler, basic) {
32  char seed = 'A';
33  Sampler sampler1(model, seed), sampler2(model, 1), sampler3(model, 1);
34  EXPECT(assert_equal(kSigmas, sampler1.sigmas()));
35  EXPECT(assert_equal(kSigmas, sampler2.sigmas()));
36  EXPECT_LONGS_EQUAL(3, sampler1.dim());
37  EXPECT_LONGS_EQUAL(3, sampler2.dim());
38  Vector actual1 = sampler1.sample();
39  EXPECT_DOUBLES_EQUAL(0.0, actual1(2), tol);
40  EXPECT(assert_equal(sampler2.sample(), sampler3.sample(), tol));
41 }
42 
43 /* ************************************************************************* */
44 int main() {
45  TestResult tr;
46  return TestRegistry::runAllTests(tr);
47 }
48 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EXPECT_LONGS_EQUAL
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
gtsam::noiseModel::Diagonal::Sigmas
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:270
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
kSigmas
static const Vector3 kSigmas(1.0, 0.1, 0.0)
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
EXPECT_DOUBLES_EQUAL
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
TestResult
Definition: TestResult.h:26
gtsam::Sampler::sample
Vector sample() const
sample from distribution
Definition: Sampler.cpp:59
gtsam
traits
Definition: chartTesting.h:28
gtsam::TEST
TEST(SmartFactorBase, Pinhole)
Definition: testSmartFactorBase.cpp:38
main
int main()
Definition: testSampler.cpp:44
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
gtsam::tol
const G double tol
Definition: Group.h:79
Sampler.h
sampling from a NoiseModel
gtsam::Sampler
Definition: Sampler.h:31


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:06:41