469 lines
14 KiB
C++
469 lines
14 KiB
C++
/* ----------------------------------------------------------------------------
|
|
|
|
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
|
* Atlanta, Georgia 30332-0415
|
|
* All Rights Reserved
|
|
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
|
|
|
* See LICENSE for the license information
|
|
|
|
* -------------------------------------------------------------------------- */
|
|
|
|
/**
|
|
* @file testValues.cpp
|
|
* @author Richard Roberts
|
|
*/
|
|
|
|
#include <gtsam/nonlinear/Values.h>
|
|
#include <gtsam/inference/Symbol.h>
|
|
#include <gtsam/linear/VectorValues.h>
|
|
#include <gtsam/geometry/Pose2.h>
|
|
#include <gtsam/geometry/Pose3.h>
|
|
#include <gtsam/base/Testable.h>
|
|
#include <gtsam/base/TestableAssertions.h>
|
|
#include <gtsam/base/LieVector.h>
|
|
|
|
#include <CppUnitLite/TestHarness.h>
|
|
#include <boost/assign/std/list.hpp> // for operator +=
|
|
#include <boost/assign/list_of.hpp>
|
|
using namespace boost::assign;
|
|
#include <stdexcept>
|
|
#include <limits>
|
|
|
|
using namespace gtsam;
|
|
using namespace std;
|
|
static double inf = std::numeric_limits<double>::infinity();
|
|
|
|
// Convenience for named keys
|
|
using symbol_shorthand::X;
|
|
using symbol_shorthand::L;
|
|
|
|
const Symbol key1('v',1), key2('v',2), key3('v',3), key4('v',4);
|
|
|
|
|
|
class TestValueData {
|
|
public:
|
|
static int ConstructorCount;
|
|
static int DestructorCount;
|
|
TestValueData(const TestValueData& other) { /*cout << "Copy constructor" << endl;*/ ++ ConstructorCount; }
|
|
TestValueData() { /*cout << "Default constructor" << endl;*/ ++ ConstructorCount; }
|
|
~TestValueData() { /*cout << "Destructor" << endl;*/ ++ DestructorCount; }
|
|
};
|
|
int TestValueData::ConstructorCount = 0;
|
|
int TestValueData::DestructorCount = 0;
|
|
class TestValue {
|
|
TestValueData data_;
|
|
public:
|
|
void print(const std::string& str = "") const {}
|
|
bool equals(const TestValue& other, double tol = 1e-9) const { return true; }
|
|
size_t dim() const { return 0; }
|
|
TestValue retract(const Vector&) const { return TestValue(); }
|
|
Vector localCoordinates(const TestValue&) const { return Vector(); }
|
|
};
|
|
|
|
namespace gtsam {
|
|
namespace traits {
|
|
template <>
|
|
struct is_manifold<TestValue> : public std::true_type {};
|
|
template <>
|
|
struct dimension<TestValue> : public std::integral_constant<int, 0> {};
|
|
}
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
TEST( Values, equals1 )
|
|
{
|
|
Values expected;
|
|
LieVector v((Vector(3) << 5.0, 6.0, 7.0));
|
|
|
|
expected.insert(key1,v);
|
|
Values actual;
|
|
actual.insert(key1,v);
|
|
CHECK(assert_equal(expected,actual));
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
TEST( Values, equals2 )
|
|
{
|
|
Values cfg1, cfg2;
|
|
LieVector v1((Vector(3) << 5.0, 6.0, 7.0));
|
|
LieVector v2((Vector(3) << 5.0, 6.0, 8.0));
|
|
|
|
cfg1.insert(key1, v1);
|
|
cfg2.insert(key1, v2);
|
|
CHECK(!cfg1.equals(cfg2));
|
|
CHECK(!cfg2.equals(cfg1));
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
TEST( Values, equals_nan )
|
|
{
|
|
Values cfg1, cfg2;
|
|
LieVector v1((Vector(3) << 5.0, 6.0, 7.0));
|
|
LieVector v2((Vector(3) << inf, inf, inf));
|
|
|
|
cfg1.insert(key1, v1);
|
|
cfg2.insert(key1, v2);
|
|
CHECK(!cfg1.equals(cfg2));
|
|
CHECK(!cfg2.equals(cfg1));
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
TEST( Values, insert_good )
|
|
{
|
|
Values cfg1, cfg2, expected;
|
|
LieVector v1((Vector(3) << 5.0, 6.0, 7.0));
|
|
LieVector v2((Vector(3) << 8.0, 9.0, 1.0));
|
|
LieVector v3((Vector(3) << 2.0, 4.0, 3.0));
|
|
LieVector v4((Vector(3) << 8.0, 3.0, 7.0));
|
|
|
|
cfg1.insert(key1, v1);
|
|
cfg1.insert(key2, v2);
|
|
cfg2.insert(key3, v4);
|
|
|
|
cfg1.insert(cfg2);
|
|
|
|
expected.insert(key1, v1);
|
|
expected.insert(key2, v2);
|
|
expected.insert(key3, v4);
|
|
|
|
CHECK(assert_equal(expected, cfg1));
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
TEST( Values, insert_bad )
|
|
{
|
|
Values cfg1, cfg2;
|
|
LieVector v1((Vector(3) << 5.0, 6.0, 7.0));
|
|
LieVector v2((Vector(3) << 8.0, 9.0, 1.0));
|
|
LieVector v3((Vector(3) << 2.0, 4.0, 3.0));
|
|
LieVector v4((Vector(3) << 8.0, 3.0, 7.0));
|
|
|
|
cfg1.insert(key1, v1);
|
|
cfg1.insert(key2, v2);
|
|
cfg2.insert(key2, v3);
|
|
cfg2.insert(key3, v4);
|
|
|
|
CHECK_EXCEPTION(cfg1.insert(cfg2), ValuesKeyAlreadyExists);
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
TEST( Values, update_element )
|
|
{
|
|
Values cfg;
|
|
LieVector v1((Vector(3) << 5.0, 6.0, 7.0));
|
|
LieVector v2((Vector(3) << 8.0, 9.0, 1.0));
|
|
|
|
cfg.insert(key1, v1);
|
|
CHECK(cfg.size() == 1);
|
|
CHECK(assert_equal(v1, cfg.at<LieVector>(key1)));
|
|
|
|
cfg.update(key1, v2);
|
|
CHECK(cfg.size() == 1);
|
|
CHECK(assert_equal(v2, cfg.at<LieVector>(key1)));
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
TEST(Values, basic_functions)
|
|
{
|
|
Values values;
|
|
const Values& values_c = values;
|
|
values.insert(2, LieVector());
|
|
values.insert(4, LieVector());
|
|
values.insert(6, LieVector());
|
|
values.insert(8, LieVector());
|
|
|
|
// find
|
|
EXPECT_LONGS_EQUAL(4, values.find(4)->key);
|
|
EXPECT_LONGS_EQUAL(4, values_c.find(4)->key);
|
|
|
|
// lower_bound
|
|
EXPECT_LONGS_EQUAL(4, values.lower_bound(4)->key);
|
|
EXPECT_LONGS_EQUAL(4, values_c.lower_bound(4)->key);
|
|
EXPECT_LONGS_EQUAL(4, values.lower_bound(3)->key);
|
|
EXPECT_LONGS_EQUAL(4, values_c.lower_bound(3)->key);
|
|
|
|
// upper_bound
|
|
EXPECT_LONGS_EQUAL(6, values.upper_bound(4)->key);
|
|
EXPECT_LONGS_EQUAL(6, values_c.upper_bound(4)->key);
|
|
EXPECT_LONGS_EQUAL(4, values.upper_bound(3)->key);
|
|
EXPECT_LONGS_EQUAL(4, values_c.upper_bound(3)->key);
|
|
|
|
}
|
|
|
|
///* ************************************************************************* */
|
|
//TEST(Values, dim_zero)
|
|
//{
|
|
// Values config0;
|
|
// config0.insert(key1, LieVector((Vector(2) << 2.0, 3.0));
|
|
// config0.insert(key2, LieVector((Vector(3) << 5.0, 6.0, 7.0));
|
|
// LONGS_EQUAL(5, config0.dim());
|
|
//
|
|
// VectorValues expected;
|
|
// expected.insert(key1, zero(2));
|
|
// expected.insert(key2, zero(3));
|
|
// CHECK(assert_equal(expected, config0.zero()));
|
|
//}
|
|
|
|
/* ************************************************************************* */
|
|
TEST(Values, expmap_a)
|
|
{
|
|
Values config0;
|
|
config0.insert(key1, LieVector((Vector(3) << 1.0, 2.0, 3.0)));
|
|
config0.insert(key2, LieVector((Vector(3) << 5.0, 6.0, 7.0)));
|
|
|
|
VectorValues increment = pair_list_of<Key, Vector>
|
|
(key1, (Vector(3) << 1.0, 1.1, 1.2))
|
|
(key2, (Vector(3) << 1.3, 1.4, 1.5));
|
|
|
|
Values expected;
|
|
expected.insert(key1, LieVector((Vector(3) << 2.0, 3.1, 4.2)));
|
|
expected.insert(key2, LieVector((Vector(3) << 6.3, 7.4, 8.5)));
|
|
|
|
CHECK(assert_equal(expected, config0.retract(increment)));
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
TEST(Values, expmap_b)
|
|
{
|
|
Values config0;
|
|
config0.insert(key1, LieVector((Vector(3) << 1.0, 2.0, 3.0)));
|
|
config0.insert(key2, LieVector((Vector(3) << 5.0, 6.0, 7.0)));
|
|
|
|
VectorValues increment = pair_list_of<Key, Vector>
|
|
(key2, (Vector(3) << 1.3, 1.4, 1.5));
|
|
|
|
Values expected;
|
|
expected.insert(key1, LieVector((Vector(3) << 1.0, 2.0, 3.0)));
|
|
expected.insert(key2, LieVector((Vector(3) << 6.3, 7.4, 8.5)));
|
|
|
|
CHECK(assert_equal(expected, config0.retract(increment)));
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
//TEST(Values, expmap_c)
|
|
//{
|
|
// Values config0;
|
|
// config0.insert(key1, LieVector((Vector(3) << 1.0, 2.0, 3.0)));
|
|
// config0.insert(key2, LieVector((Vector(3) << 5.0, 6.0, 7.0)));
|
|
//
|
|
// Vector increment = LieVector(6,
|
|
// 1.0, 1.1, 1.2,
|
|
// 1.3, 1.4, 1.5);
|
|
//
|
|
// Values expected;
|
|
// expected.insert(key1, LieVector((Vector(3) << 2.0, 3.1, 4.2)));
|
|
// expected.insert(key2, LieVector((Vector(3) << 6.3, 7.4, 8.5)));
|
|
//
|
|
// CHECK(assert_equal(expected, config0.retract(increment)));
|
|
//}
|
|
|
|
/* ************************************************************************* */
|
|
TEST(Values, expmap_d)
|
|
{
|
|
Values config0;
|
|
config0.insert(key1, LieVector((Vector(3) << 1.0, 2.0, 3.0)));
|
|
config0.insert(key2, LieVector((Vector(3) << 5.0, 6.0, 7.0)));
|
|
//config0.print("config0");
|
|
CHECK(equal(config0, config0));
|
|
CHECK(config0.equals(config0));
|
|
|
|
Values poseconfig;
|
|
poseconfig.insert(key1, Pose2(1,2,3));
|
|
poseconfig.insert(key2, Pose2(0.3, 0.4, 0.5));
|
|
|
|
CHECK(equal(config0, config0));
|
|
CHECK(config0.equals(config0));
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
TEST(Values, localCoordinates)
|
|
{
|
|
Values valuesA;
|
|
valuesA.insert(key1, LieVector((Vector(3) << 1.0, 2.0, 3.0)));
|
|
valuesA.insert(key2, LieVector((Vector(3) << 5.0, 6.0, 7.0)));
|
|
|
|
VectorValues expDelta = pair_list_of<Key, Vector>
|
|
(key1, (Vector(3) << 0.1, 0.2, 0.3))
|
|
(key2, (Vector(3) << 0.4, 0.5, 0.6));
|
|
|
|
Values valuesB = valuesA.retract(expDelta);
|
|
|
|
EXPECT(assert_equal(expDelta, valuesA.localCoordinates(valuesB)));
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
TEST(Values, extract_keys)
|
|
{
|
|
Values config;
|
|
|
|
config.insert(key1, Pose2());
|
|
config.insert(key2, Pose2());
|
|
config.insert(key3, Pose2());
|
|
config.insert(key4, Pose2());
|
|
|
|
FastList<Key> expected, actual;
|
|
expected += key1, key2, key3, key4;
|
|
actual = config.keys();
|
|
|
|
CHECK(actual.size() == expected.size());
|
|
FastList<Key>::const_iterator itAct = actual.begin(), itExp = expected.begin();
|
|
for (; itAct != actual.end() && itExp != expected.end(); ++itAct, ++itExp) {
|
|
EXPECT(*itExp == *itAct);
|
|
}
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
TEST(Values, exists_)
|
|
{
|
|
Values config0;
|
|
config0.insert(key1, LieVector((Vector(1) << 1.)));
|
|
config0.insert(key2, LieVector((Vector(1) << 2.)));
|
|
|
|
boost::optional<const LieVector&> v = config0.exists<LieVector>(key1);
|
|
CHECK(assert_equal((Vector(1) << 1.),*v));
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
TEST(Values, update)
|
|
{
|
|
Values config0;
|
|
config0.insert(key1, LieVector((Vector(1) << 1.)));
|
|
config0.insert(key2, LieVector((Vector(1) << 2.)));
|
|
|
|
Values superset;
|
|
superset.insert(key1, LieVector((Vector(1) << -1.)));
|
|
superset.insert(key2, LieVector((Vector(1) << -2.)));
|
|
config0.update(superset);
|
|
|
|
Values expected;
|
|
expected.insert(key1, LieVector((Vector(1) << -1.)));
|
|
expected.insert(key2, LieVector((Vector(1) << -2.)));
|
|
CHECK(assert_equal(expected,config0));
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
TEST(Values, filter) {
|
|
Pose2 pose0(1.0, 2.0, 0.3);
|
|
Pose3 pose1(Pose2(0.1, 0.2, 0.3));
|
|
Pose2 pose2(4.0, 5.0, 0.6);
|
|
Pose3 pose3(Pose2(0.3, 0.7, 0.9));
|
|
|
|
Values values;
|
|
values.insert(0, pose0);
|
|
values.insert(1, pose1);
|
|
values.insert(2, pose2);
|
|
values.insert(3, pose3);
|
|
|
|
// Filter by key
|
|
int i = 0;
|
|
Values::Filtered<Value> filtered = values.filter(boost::bind(std::greater_equal<Key>(), _1, 2));
|
|
EXPECT_LONGS_EQUAL(2, (long)filtered.size());
|
|
BOOST_FOREACH(const Values::Filtered<>::KeyValuePair& key_value, filtered) {
|
|
if(i == 0) {
|
|
LONGS_EQUAL(2, (long)key_value.key);
|
|
try {key_value.value.cast<Pose2>();} catch (const std::bad_cast& e) { FAIL("can't cast Value to Pose2");}
|
|
THROWS_EXCEPTION(key_value.value.cast<Pose3>());
|
|
EXPECT(assert_equal(pose2, key_value.value.cast<Pose2>()));
|
|
} else if(i == 1) {
|
|
LONGS_EQUAL(3, (long)key_value.key);
|
|
try {key_value.value.cast<Pose3>();} catch (const std::bad_cast& e) { FAIL("can't cast Value to Pose3");}
|
|
THROWS_EXCEPTION(key_value.value.cast<Pose2>());
|
|
EXPECT(assert_equal(pose3, key_value.value.cast<Pose3>()));
|
|
} else {
|
|
EXPECT(false);
|
|
}
|
|
++ i;
|
|
}
|
|
EXPECT_LONGS_EQUAL(2, (long)i);
|
|
|
|
// construct a values with the view
|
|
Values actualSubValues1(filtered);
|
|
Values expectedSubValues1;
|
|
expectedSubValues1.insert(2, pose2);
|
|
expectedSubValues1.insert(3, pose3);
|
|
EXPECT(assert_equal(expectedSubValues1, actualSubValues1));
|
|
|
|
// Filter by type
|
|
i = 0;
|
|
Values::ConstFiltered<Pose3> pose_filtered = values.filter<Pose3>();
|
|
EXPECT_LONGS_EQUAL(2, (long)pose_filtered.size());
|
|
BOOST_FOREACH(const Values::ConstFiltered<Pose3>::KeyValuePair& key_value, pose_filtered) {
|
|
if(i == 0) {
|
|
EXPECT_LONGS_EQUAL(1, (long)key_value.key);
|
|
EXPECT(assert_equal(pose1, key_value.value));
|
|
} else if(i == 1) {
|
|
EXPECT_LONGS_EQUAL(3, (long)key_value.key);
|
|
EXPECT(assert_equal(pose3, key_value.value));
|
|
} else {
|
|
EXPECT(false);
|
|
}
|
|
++ i;
|
|
}
|
|
EXPECT_LONGS_EQUAL(2, (long)i);
|
|
|
|
// construct a values with the view
|
|
Values actualSubValues2(pose_filtered);
|
|
Values expectedSubValues2;
|
|
expectedSubValues2.insert(1, pose1);
|
|
expectedSubValues2.insert(3, pose3);
|
|
EXPECT(assert_equal(expectedSubValues2, actualSubValues2));
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
TEST(Values, Symbol_filter) {
|
|
Pose2 pose0(1.0, 2.0, 0.3);
|
|
Pose3 pose1(Pose2(0.1, 0.2, 0.3));
|
|
Pose2 pose2(4.0, 5.0, 0.6);
|
|
Pose3 pose3(Pose2(0.3, 0.7, 0.9));
|
|
|
|
Values values;
|
|
values.insert(X(0), pose0);
|
|
values.insert(Symbol('y',1), pose1);
|
|
values.insert(X(2), pose2);
|
|
values.insert(Symbol('y',3), pose3);
|
|
|
|
int i = 0;
|
|
BOOST_FOREACH(const Values::Filtered<Value>::KeyValuePair& key_value, values.filter(Symbol::ChrTest('y'))) {
|
|
if(i == 0) {
|
|
LONGS_EQUAL(Symbol('y', 1), (long)key_value.key);
|
|
EXPECT(assert_equal(pose1, key_value.value.cast<Pose3>()));
|
|
} else if(i == 1) {
|
|
LONGS_EQUAL(Symbol('y', 3), (long)key_value.key);
|
|
EXPECT(assert_equal(pose3, key_value.value.cast<Pose3>()));
|
|
} else {
|
|
EXPECT(false);
|
|
}
|
|
++ i;
|
|
}
|
|
LONGS_EQUAL(2, (long)i);
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
TEST(Values, Destructors) {
|
|
// Check that Value destructors are called when Values container is deleted
|
|
{
|
|
Values values;
|
|
{
|
|
TestValue value1;
|
|
TestValue value2;
|
|
LONGS_EQUAL(2, (long)TestValueData::ConstructorCount);
|
|
LONGS_EQUAL(0, (long)TestValueData::DestructorCount);
|
|
values.insert(0, value1);
|
|
values.insert(1, value2);
|
|
}
|
|
// additional 2 con/destructor counts for the temporary
|
|
// GenericValue<TestValue> in insert()
|
|
// but I'm sure some advanced programmer can figure out
|
|
// a way to avoid the temporary, or optimize it out
|
|
LONGS_EQUAL(4+2, (long)TestValueData::ConstructorCount);
|
|
LONGS_EQUAL(2+2, (long)TestValueData::DestructorCount);
|
|
}
|
|
LONGS_EQUAL(4+2, (long)TestValueData::ConstructorCount);
|
|
LONGS_EQUAL(4+2, (long)TestValueData::DestructorCount);
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
|
|
/* ************************************************************************* */
|