Remove Values code deprecated in 4.2
parent
d39ac70bdf
commit
46e466b22d
|
@ -109,174 +109,6 @@ namespace gtsam {
|
|||
return result;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
template<class ValueType>
|
||||
class Values::Filtered {
|
||||
public:
|
||||
/** A key-value pair, with the value a specific derived Value type. */
|
||||
typedef _ValuesKeyValuePair<ValueType> KeyValuePair;
|
||||
typedef _ValuesConstKeyValuePair<ValueType> ConstKeyValuePair;
|
||||
typedef KeyValuePair value_type;
|
||||
|
||||
typedef
|
||||
boost::transform_iterator<
|
||||
KeyValuePair(*)(Values::KeyValuePair),
|
||||
boost::filter_iterator<
|
||||
std::function<bool(const Values::ConstKeyValuePair&)>,
|
||||
Values::iterator> >
|
||||
iterator;
|
||||
|
||||
typedef iterator const_iterator;
|
||||
|
||||
typedef
|
||||
boost::transform_iterator<
|
||||
ConstKeyValuePair(*)(Values::ConstKeyValuePair),
|
||||
boost::filter_iterator<
|
||||
std::function<bool(const Values::ConstKeyValuePair&)>,
|
||||
Values::const_iterator> >
|
||||
const_const_iterator;
|
||||
|
||||
iterator begin() { return begin_; }
|
||||
iterator end() { return end_; }
|
||||
const_iterator begin() const { return begin_; }
|
||||
const_iterator end() const { return end_; }
|
||||
const_const_iterator beginConst() const { return constBegin_; }
|
||||
const_const_iterator endConst() const { return constEnd_; }
|
||||
|
||||
/** Returns the number of values in this view */
|
||||
size_t size() const {
|
||||
size_t i = 0;
|
||||
for (const_const_iterator it = beginConst(); it != endConst(); ++it)
|
||||
++i;
|
||||
return i;
|
||||
}
|
||||
|
||||
private:
|
||||
Filtered(
|
||||
const std::function<bool(const Values::ConstKeyValuePair&)>& filter,
|
||||
Values& values) :
|
||||
begin_(
|
||||
boost::make_transform_iterator(
|
||||
boost::make_filter_iterator(filter, values.begin(), values.end()),
|
||||
&ValuesCastHelper<ValueType, KeyValuePair, Values::KeyValuePair>::cast)), end_(
|
||||
boost::make_transform_iterator(
|
||||
boost::make_filter_iterator(filter, values.end(), values.end()),
|
||||
&ValuesCastHelper<ValueType, KeyValuePair, Values::KeyValuePair>::cast)), constBegin_(
|
||||
boost::make_transform_iterator(
|
||||
boost::make_filter_iterator(filter,
|
||||
((const Values&) values).begin(),
|
||||
((const Values&) values).end()),
|
||||
&ValuesCastHelper<ValueType, ConstKeyValuePair,
|
||||
Values::ConstKeyValuePair>::cast)), constEnd_(
|
||||
boost::make_transform_iterator(
|
||||
boost::make_filter_iterator(filter,
|
||||
((const Values&) values).end(),
|
||||
((const Values&) values).end()),
|
||||
&ValuesCastHelper<ValueType, ConstKeyValuePair,
|
||||
Values::ConstKeyValuePair>::cast)) {
|
||||
}
|
||||
|
||||
friend class Values;
|
||||
iterator begin_;
|
||||
iterator end_;
|
||||
const_const_iterator constBegin_;
|
||||
const_const_iterator constEnd_;
|
||||
};
|
||||
|
||||
template<class ValueType>
|
||||
class Values::ConstFiltered {
|
||||
public:
|
||||
/** A const key-value pair, with the value a specific derived Value type. */
|
||||
typedef _ValuesConstKeyValuePair<ValueType> KeyValuePair;
|
||||
typedef KeyValuePair value_type;
|
||||
|
||||
typedef typename Filtered<ValueType>::const_const_iterator iterator;
|
||||
typedef typename Filtered<ValueType>::const_const_iterator const_iterator;
|
||||
|
||||
/** Conversion from Filtered to ConstFiltered */
|
||||
ConstFiltered(const Filtered<ValueType>& rhs) :
|
||||
begin_(rhs.beginConst()),
|
||||
end_(rhs.endConst()) {}
|
||||
|
||||
iterator begin() { return begin_; }
|
||||
iterator end() { return end_; }
|
||||
const_iterator begin() const { return begin_; }
|
||||
const_iterator end() const { return end_; }
|
||||
|
||||
/** Returns the number of values in this view */
|
||||
size_t size() const {
|
||||
size_t i = 0;
|
||||
for (const_iterator it = begin(); it != end(); ++it)
|
||||
++i;
|
||||
return i;
|
||||
}
|
||||
|
||||
FastList<Key> keys() const {
|
||||
FastList<Key> result;
|
||||
for(const_iterator it = begin(); it != end(); ++it)
|
||||
result.push_back(it->key);
|
||||
return result;
|
||||
}
|
||||
|
||||
private:
|
||||
friend class Values;
|
||||
const_iterator begin_;
|
||||
const_iterator end_;
|
||||
ConstFiltered(
|
||||
const std::function<bool(const Values::ConstKeyValuePair&)>& filter,
|
||||
const Values& values) {
|
||||
// We remove the const from values to create a non-const Filtered
|
||||
// view, then pull the const_iterators out of it.
|
||||
const Filtered<ValueType> filtered(filter, const_cast<Values&>(values));
|
||||
begin_ = filtered.beginConst();
|
||||
end_ = filtered.endConst();
|
||||
}
|
||||
};
|
||||
|
||||
template<class ValueType>
|
||||
Values::Values(const Values::Filtered<ValueType>& view) {
|
||||
for(const auto key_value: view) {
|
||||
Key key = key_value.key;
|
||||
insert(key, static_cast<const ValueType&>(key_value.value));
|
||||
}
|
||||
}
|
||||
|
||||
template<class ValueType>
|
||||
Values::Values(const Values::ConstFiltered<ValueType>& view) {
|
||||
for(const auto key_value: view) {
|
||||
Key key = key_value.key;
|
||||
insert(key, static_cast<const ValueType&>(key_value.value));
|
||||
}
|
||||
}
|
||||
|
||||
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<>
|
||||
inline bool Values::filterHelper<Value>(const std::function<bool(Key)> filter,
|
||||
|
|
|
@ -168,14 +168,6 @@ namespace gtsam {
|
|||
}
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
std::pair<Values::iterator, bool> Values::tryInsert(Key j, const Value& value) {
|
||||
std::pair<KeyValueMap::iterator, bool> result = values_.insert(j, value.clone_());
|
||||
return std::make_pair(boost::make_transform_iterator(result.first, &make_deref_pair), result.second);
|
||||
}
|
||||
#endif
|
||||
|
||||
/* ************************************************************************* */
|
||||
void Values::update(Key j, const Value& val) {
|
||||
// Find the value to update
|
||||
|
|
|
@ -30,10 +30,6 @@
|
|||
#include <gtsam/inference/Key.h>
|
||||
#include <boost/ptr_container/serialize_ptr_map.hpp>
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
#include <boost/iterator/transform_iterator.hpp>
|
||||
#include <boost/iterator/filter_iterator.hpp>
|
||||
#endif
|
||||
|
||||
#include <string>
|
||||
#include <utility>
|
||||
|
@ -301,103 +297,6 @@ namespace gtsam {
|
|||
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
|
||||
// Types obtained by iterating
|
||||
typedef KeyValueMap::const_iterator::value_type ConstKeyValuePtrPair;
|
||||
typedef KeyValueMap::iterator::value_type KeyValuePtrPair;
|
||||
|
||||
/// Mutable forward iterator, with value type KeyValuePair
|
||||
typedef boost::transform_iterator<
|
||||
std::function<KeyValuePair(const KeyValuePtrPair&)>, KeyValueMap::iterator> iterator;
|
||||
|
||||
/// Const forward iterator, with value type ConstKeyValuePair
|
||||
typedef boost::transform_iterator<
|
||||
std::function<ConstKeyValuePair(const ConstKeyValuePtrPair&)>, KeyValueMap::const_iterator> const_iterator;
|
||||
|
||||
/// Mutable reverse iterator, with value type KeyValuePair
|
||||
typedef boost::transform_iterator<
|
||||
std::function<KeyValuePair(const KeyValuePtrPair&)>, KeyValueMap::reverse_iterator> reverse_iterator;
|
||||
|
||||
/// Const reverse iterator, with value type ConstKeyValuePair
|
||||
typedef boost::transform_iterator<
|
||||
std::function<ConstKeyValuePair(const ConstKeyValuePtrPair&)>, KeyValueMap::const_reverse_iterator> const_reverse_iterator;
|
||||
|
||||
/** insert that mimics the STL map insert - if the value already exists, the map is not modified
|
||||
* and an iterator to the existing value is returned, along with 'false'. If the value did not
|
||||
* exist, it is inserted and an iterator pointing to the new element, along with 'true', is
|
||||
* returned. */
|
||||
std::pair<iterator, bool> tryInsert(Key j, const Value& value);
|
||||
|
||||
static ConstKeyValuePair make_const_deref_pair(const KeyValueMap::const_iterator::value_type& key_value) {
|
||||
return ConstKeyValuePair(key_value.first, *key_value.second); }
|
||||
|
||||
static KeyValuePair make_deref_pair(const KeyValueMap::iterator::value_type& key_value) {
|
||||
return KeyValuePair(key_value.first, *key_value.second); }
|
||||
|
||||
const_iterator begin() const { return boost::make_transform_iterator(values_.begin(), &make_const_deref_pair); }
|
||||
const_iterator end() const { return boost::make_transform_iterator(values_.end(), &make_const_deref_pair); }
|
||||
iterator begin() { return boost::make_transform_iterator(values_.begin(), &make_deref_pair); }
|
||||
iterator end() { return boost::make_transform_iterator(values_.end(), &make_deref_pair); }
|
||||
const_reverse_iterator rbegin() const { return boost::make_transform_iterator(values_.rbegin(), &make_const_deref_pair); }
|
||||
const_reverse_iterator rend() const { return boost::make_transform_iterator(values_.rend(), &make_const_deref_pair); }
|
||||
reverse_iterator rbegin() { return boost::make_transform_iterator(values_.rbegin(), &make_deref_pair); }
|
||||
reverse_iterator rend() { return boost::make_transform_iterator(values_.rend(), &make_deref_pair); }
|
||||
|
||||
/** Find an element by key, returning an iterator, or end() if the key was
|
||||
* not found. */
|
||||
iterator find(Key j) { return boost::make_transform_iterator(values_.find(j), &make_deref_pair); }
|
||||
|
||||
/** Find an element by key, returning an iterator, or end() if the key was
|
||||
* not found. */
|
||||
const_iterator find(Key j) const { return boost::make_transform_iterator(values_.find(j), &make_const_deref_pair); }
|
||||
|
||||
/** Find the element greater than or equal to the specified key. */
|
||||
iterator lower_bound(Key j) { return boost::make_transform_iterator(values_.lower_bound(j), &make_deref_pair); }
|
||||
|
||||
/** Find the element greater than or equal to the specified key. */
|
||||
const_iterator lower_bound(Key j) const { return boost::make_transform_iterator(values_.lower_bound(j), &make_const_deref_pair); }
|
||||
|
||||
/** Find the lowest-ordered element greater than the specified key. */
|
||||
iterator upper_bound(Key j) { return boost::make_transform_iterator(values_.upper_bound(j), &make_deref_pair); }
|
||||
|
||||
/** Find the lowest-ordered element greater than the specified key. */
|
||||
const_iterator upper_bound(Key j) const { return boost::make_transform_iterator(values_.upper_bound(j), &make_const_deref_pair); }
|
||||
|
||||
/** 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>);
|
||||
|
||||
/// A filtered view of the original Values class, const version.
|
||||
ConstFiltered<Value> GTSAM_DEPRECATED
|
||||
filter(const std::function<bool(Key)>& filterFcn) const;
|
||||
|
||||
/// 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-
|
||||
// supplied \c filter function.
|
||||
|
|
|
@ -199,25 +199,6 @@ TEST(Values, basic_functions)
|
|||
EXPECT(values.exists(4));
|
||||
EXPECT(values.exists(6));
|
||||
EXPECT(values.exists(8));
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
// find
|
||||
const Values& values_c = values;
|
||||
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);
|
||||
#endif
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
Loading…
Reference in New Issue