Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Deprecate filter #1397

Merged
merged 1 commit into from
Jan 20, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
29 changes: 20 additions & 9 deletions gtsam/nonlinear/Values-inl.h
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,25 @@ namespace gtsam {
}
};

/* ************************************************************************* */
/* ************************************************************************* */
template <class ValueType>
std::map<Key, ValueType>
Values::extract(const std::function<bool(Key)>& filterFcn) const {
std::map<Key, ValueType> result;
for (const auto& key_value : *this) {
// Check if key matches
if (filterFcn(key_value.key)) {
// Check if type matches (typically does as symbols matched with types)
if (auto t =
dynamic_cast<const GenericValue<ValueType>*>(&key_value.value))
result[key_value.key] = t->value();
}
}
return result;
}

/* ************************************************************************* */
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
template<class ValueType>
class Values::Filtered {
public:
Expand Down Expand Up @@ -164,7 +182,6 @@ namespace gtsam {
const_const_iterator constEnd_;
};

/* ************************************************************************* */
template<class ValueType>
class Values::ConstFiltered {
public:
Expand Down Expand Up @@ -215,8 +232,6 @@ namespace gtsam {
}
};

/* ************************************************************************* */
/** Constructor from a Filtered view copies out all values */
template<class ValueType>
Values::Values(const Values::Filtered<ValueType>& view) {
for(const auto key_value: view) {
Expand All @@ -225,7 +240,6 @@ namespace gtsam {
}
}

/* ************************************************************************* */
template<class ValueType>
Values::Values(const Values::ConstFiltered<ValueType>& view) {
for(const auto key_value: view) {
Expand All @@ -234,33 +248,30 @@ namespace gtsam {
}
}

/* ************************************************************************* */
Values::Filtered<Value>
inline Values::filter(const std::function<bool(Key)>& filterFcn) {
return filter<Value>(filterFcn);
}

/* ************************************************************************* */
template<class ValueType>
Values::Filtered<ValueType>
Values::filter(const std::function<bool(Key)>& filterFcn) {
return Filtered<ValueType>(std::bind(&filterHelper<ValueType>, filterFcn,
std::placeholders::_1), *this);
}

/* ************************************************************************* */
Values::ConstFiltered<Value>
inline Values::filter(const std::function<bool(Key)>& filterFcn) const {
return filter<Value>(filterFcn);
}

/* ************************************************************************* */
template<class ValueType>
Values::ConstFiltered<ValueType>
Values::filter(const std::function<bool(Key)>& filterFcn) const {
return ConstFiltered<ValueType>(std::bind(&filterHelper<ValueType>,
filterFcn, std::placeholders::_1), *this);
}
#endif

/* ************************************************************************* */
template<>
Expand Down
140 changes: 54 additions & 86 deletions gtsam/nonlinear/Values.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,9 +29,11 @@
#include <gtsam/base/VectorSpace.h>
#include <gtsam/inference/Key.h>
#include <boost/iterator/transform_iterator.hpp>
#include <boost/iterator/filter_iterator.hpp>
#include <boost/ptr_container/serialize_ptr_map.hpp>
#include <boost/shared_ptr.hpp>
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
#include <boost/iterator/filter_iterator.hpp>
#endif

#include <string>
#include <utility>
Expand Down Expand Up @@ -126,14 +128,6 @@ namespace gtsam {

typedef KeyValuePair value_type;

/** A filtered view of a Values, returned from Values::filter. */
template<class ValueType = Value>
class Filtered;

/** A filtered view of a const Values, returned from Values::filter. */
template<class ValueType = Value>
class ConstFiltered;

/** Default constructor creates an empty Values class */
Values() {}

Expand All @@ -153,14 +147,6 @@ namespace gtsam {
/** Construct from a Values and an update vector: identical to other.retract(delta) */
Values(const Values& other, const VectorValues& delta);

/** Constructor from a Filtered view copies out all values */
template<class ValueType>
Values(const Filtered<ValueType>& view);

/** Constructor from a Filtered or ConstFiltered view */
template<class ValueType>
Values(const ConstFiltered<ValueType>& view);

/// @name Testable
/// @{

Expand Down Expand Up @@ -322,30 +308,26 @@ namespace gtsam {
/** Return a VectorValues of zero vectors for each variable in this Values */
VectorValues zeroVectors() const;

/**
* Return a filtered view of this Values class, without copying any data.
* When iterating over the filtered view, only the key-value pairs
* with a key causing \c filterFcn to return \c true are visited. Because
* the object Filtered<Value> returned from filter() is only a
* <em>view</em> the original Values object must not be deallocated or
* go out of scope as long as the view is needed.
* @param filterFcn The function that determines which key-value pairs are
* included in the filtered view, for which this function returns \c true
* on their keys.
* @return A filtered view of the original Values class, which references
* the original Values class.
*/
Filtered<Value>
filter(const std::function<bool(Key)>& filterFcn);
// Count values of given type \c ValueType
template<class ValueType>
size_t count() const {
size_t i = 0;
for (const auto key_value : *this) {
if (dynamic_cast<const GenericValue<ValueType>*>(&key_value.value))
++i;
}
return i;
}

/**
* Return a filtered view of this Values class, without copying any data.
* Extract a subset of values of the given type \c ValueType.
*
* In this templated version, only key-value pairs whose value matches the
* template argument \c ValueType and whose key causes the function argument
* \c filterFcn to return true are visited when iterating over the filtered
* view. Because the object Filtered<Value> returned from filter() is only
* a <em>view</em> the original Values object must not be deallocated or
* go out of scope as long as the view is needed.
* view. This replaces the fancier but very boost-dependent \c filter methods
* that were previously available up to GTSAM 4.2.
*
* @tparam ValueType The type that the value in a key-value pair must match
* to be included in the filtered view. Currently, base classes are not
* resolved so the type must match exactly, except if ValueType = Value, in
Expand All @@ -354,61 +336,47 @@ namespace gtsam {
* included in the filtered view, for which this function returns \c true
* on their keys (default: always return true so that filter() only
* filters by type, matching \c ValueType).
* @return A filtered view of the original Values class, which references
* the original Values class.
* @return An Eigen aligned map on Key with the filtered values.
*/
template<class ValueType>
Filtered<ValueType>
template <class ValueType>
std::map<Key, ValueType> // , std::less<Key>, Eigen::aligned_allocator<ValueType>
extract(const std::function<bool(Key)>& filterFcn = &_truePredicate<Key>) const;

#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
/** A filtered view of a Values, returned from Values::filter. */
template <class ValueType = Value>
class Filtered;

/** A filtered view of a const Values, returned from Values::filter. */
template <class ValueType = Value>
class ConstFiltered;

/** Constructor from a Filtered view copies out all values */
template <class ValueType>
Values(const Filtered<ValueType>& view);

/** Constructor from a Filtered or ConstFiltered view */
template <class ValueType>
Values(const ConstFiltered<ValueType>& view);

/// A filtered view of the original Values class.
Filtered<Value> GTSAM_DEPRECATED
filter(const std::function<bool(Key)>& filterFcn);

/// A filtered view of the original Values class, also filter on type.
template <class ValueType>
Filtered<ValueType> GTSAM_DEPRECATED
filter(const std::function<bool(Key)>& filterFcn = &_truePredicate<Key>);

/**
* Return a filtered view of this Values class, without copying any data.
* When iterating over the filtered view, only the key-value pairs
* with a key causing \c filterFcn to return \c true are visited. Because
* the object Filtered<Value> returned from filter() is only a
* <em>view</em> the original Values object must not be deallocated or
* go out of scope as long as the view is needed.
* @param filterFcn The function that determines which key-value pairs are
* included in the filtered view, for which this function returns \c true
* on their keys.
* @return A filtered view of the original Values class, which references
* the original Values class.
*/
ConstFiltered<Value>
/// A filtered view of the original Values class, const version.
ConstFiltered<Value> GTSAM_DEPRECATED
filter(const std::function<bool(Key)>& filterFcn) const;

/**
* Return a filtered view of this Values class, without copying any data.
* In this templated version, only key-value pairs whose value matches the
* template argument \c ValueType and whose key causes the function argument
* \c filterFcn to return true are visited when iterating over the filtered
* view. Because the object Filtered<Value> returned from filter() is only
* a <em>view</em> the original Values object must not be deallocated or
* go out of scope as long as the view is needed.
* @tparam ValueType The type that the value in a key-value pair must match
* to be included in the filtered view. Currently, base classes are not
* resolved so the type must match exactly, except if ValueType = Value, in
* which case no type filtering is done.
* @param filterFcn The function that determines which key-value pairs are
* included in the filtered view, for which this function returns \c true
* on their keys.
* @return A filtered view of the original Values class, which references
* the original Values class.
*/
template<class ValueType>
ConstFiltered<ValueType>
filter(const std::function<bool(Key)>& filterFcn = &_truePredicate<Key>) const;

// Count values of given type \c ValueType
template<class ValueType>
size_t count() const {
size_t i = 0;
for (const auto key_value : *this) {
if (dynamic_cast<const GenericValue<ValueType>*>(&key_value.value))
++i;
}
return i;
}
/// A filtered view of the original Values class, also on type, const.
template <class ValueType>
ConstFiltered<ValueType> GTSAM_DEPRECATED filter(
const std::function<bool(Key)>& filterFcn = &_truePredicate<Key>) const;
#endif

private:
// Filters based on ValueType (if not Value) and also based on the user-
Expand Down
20 changes: 18 additions & 2 deletions gtsam/nonlinear/tests/testValues.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -343,6 +343,7 @@ TEST(Values, filter) {
values.insert(2, pose2);
values.insert(3, pose3);

#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
// Filter by key
int i = 0;
Values::Filtered<Value> filtered = values.filter(std::bind(std::greater_equal<Key>(), std::placeholders::_1, 2));
Expand Down Expand Up @@ -395,15 +396,23 @@ TEST(Values, filter) {
++ i;
}
EXPECT_LONGS_EQUAL(2, (long)i);
EXPECT_LONGS_EQUAL(2, (long)values.count<Pose3>());
EXPECT_LONGS_EQUAL(2, (long)values.count<Pose2>());

// 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));
#endif

// Test counting by type.
EXPECT_LONGS_EQUAL(2, (long)values.count<Pose3>());
EXPECT_LONGS_EQUAL(2, (long)values.count<Pose2>());

// Filter by type using extract.
auto extracted_pose3s = values.extract<Pose3>();
EXPECT_LONGS_EQUAL(2, (long)extracted_pose3s.size());

}

/* ************************************************************************* */
Expand All @@ -419,6 +428,7 @@ TEST(Values, Symbol_filter) {
values.insert(X(2), pose2);
values.insert(Symbol('y', 3), pose3);

#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
int i = 0;
for(const auto key_value: values.filter(Symbol::ChrTest('y'))) {
if(i == 0) {
Expand All @@ -433,6 +443,12 @@ TEST(Values, Symbol_filter) {
++ i;
}
LONGS_EQUAL(2, (long)i);
#endif

// Test extract with filter on symbol:
auto extracted_pose3s = values.extract<Pose3>(Symbol::ChrTest('y'));
EXPECT_LONGS_EQUAL(2, (long)extracted_pose3s.size());

}

/* ************************************************************************* */
Expand Down
Loading