21 #ifdef PYBIND11_HAS_OPTIONAL 23 #endif // PYBIND11_HAS_OPTIONAL 40 template <
typename A,
typename B>
42 return !(*it).first || !(*it).second;
69 value_ =
other.value_;
73 int get()
const {
return value_; }
84 template <
typename PythonType>
87 throw py::value_error(
"Please provide at least 5 elements for testing.");
90 auto checks = py::list();
92 auto result = PyObject_RichCompareBool(a.ptr(),
b.ptr(), Py_EQ);
94 throw py::error_already_set();
96 checks.append(
result != 0);
114 assert_equal((it + 1)->attr(
"real"), x[1].attr(
"real"));
121 checks.append(static_cast<std::size_t>(x.end() - x.begin()) == x.size());
122 checks.append((x.begin() +
static_cast<std::ptrdiff_t
>(x.size())) == x.end());
123 checks.append(x.begin() < x.end());
132 explicit Sliceable(
int n) :
size(n) {}
133 int start, stop,
step;
136 py::class_<Sliceable>(
m,
"Sliceable")
137 .def(py::init<int>())
138 .def(
"__getitem__", [](
const Sliceable &
s,
const py::slice &
slice) {
140 if (!slice.compute(s.size, &start, &stop, &
step, &slicelength)) {
141 throw py::error_already_set();
143 int istart =
static_cast<int>(start);
144 int istop =
static_cast<int>(stop);
145 int istep =
static_cast<int>(
step);
149 m.def(
"make_forward_slice_size_t", []() {
return py::slice(0, -1, 1); });
150 m.def(
"make_reversed_slice_object",
151 []() {
return py::slice(py::none(), py::none(), py::int_(-1)); });
152 #ifdef PYBIND11_HAS_OPTIONAL 153 m.attr(
"has_optional") =
true;
154 m.def(
"make_reversed_slice_size_t_optional_verbose",
155 []() {
return py::slice(std::nullopt, std::nullopt, -1); });
158 m.def(
"make_reversed_slice_size_t_optional", []() {
return py::slice({}, {}, -1); });
160 m.attr(
"has_optional") =
false;
169 m_data =
new float[
size];
170 memset(m_data, 0,
sizeof(
float) * size);
172 explicit Sequence(
const std::vector<float> &
value) : m_size(value.size()) {
175 m_data =
new float[m_size];
176 memcpy(m_data, &value[0],
sizeof(
float) * m_size);
181 m_data =
new float[m_size];
182 memcpy(m_data, s.m_data,
sizeof(
float) * m_size);
199 m_data =
new float[m_size];
200 memcpy(m_data, s.m_data,
sizeof(
float) * m_size);
219 if (m_size != s.size()) {
222 for (
size_t i = 0;
i < m_size; ++
i) {
223 if (m_data[
i] != s[
i]) {
231 float operator[](
size_t index)
const {
return m_data[index]; }
232 float &operator[](
size_t index) {
return m_data[index]; }
234 bool contains(
float v)
const {
235 for (
size_t i = 0;
i < m_size; ++
i) {
236 if (v == m_data[
i]) {
245 for (
size_t i = 0;
i < m_size; ++
i) {
246 result[m_size -
i - 1] = m_data[
i];
251 size_t size()
const {
return m_size; }
253 const float *begin()
const {
return m_data; }
254 const float *
end()
const {
return m_data + m_size; }
260 py::class_<Sequence>(
m,
"Sequence")
261 .def(py::init<size_t>())
262 .def(
py::init<
const std::vector<float> &>())
267 throw py::index_error();
274 throw py::index_error();
283 py::keep_alive<0, 1>() )
284 .def(
"__contains__", [](
const Sequence &s,
float v) {
return s.contains(v); })
285 .def(
"__reversed__", [](
const Sequence &s) ->
Sequence {
return s.reversed(); })
289 size_t start = 0, stop = 0,
step = 0, slicelength = 0;
290 if (!slice.compute(s.size(), &start, &stop, &
step, &slicelength)) {
291 throw py::error_already_set();
294 for (
size_t i = 0; i < slicelength; ++
i) {
295 (*seq)[
i] = s[start];
302 size_t start = 0, stop = 0,
step = 0, slicelength = 0;
303 if (!slice.compute(s.size(), &start, &stop, &
step, &slicelength)) {
304 throw py::error_already_set();
306 if (slicelength != value.size()) {
307 throw std::runtime_error(
308 "Left and right hand size of slice assignment have different sizes!");
310 for (
size_t i = 0; i < slicelength; ++
i) {
326 StringMap() =
default;
327 explicit StringMap(std::unordered_map<std::string, std::string>
init)
328 : map(std::move(init)) {}
330 void set(
const std::string &
key, std::string val) { map[
key] = std::move(val); }
331 std::string
get(
const std::string &
key)
const {
return map.at(key); }
332 size_t size()
const {
return map.size(); }
335 std::unordered_map<std::string, std::string> map;
338 decltype(map.cbegin()) begin()
const {
return map.cbegin(); }
339 decltype(map.cend())
end()
const {
return map.cend(); }
341 py::class_<StringMap>(
m,
"StringMap")
343 .def(
py::init<std::unordered_map<std::string, std::string>>())
345 [](
const StringMap &map,
const std::string &
key) {
348 }
catch (
const std::out_of_range &) {
349 throw py::key_error(
"key '" + key +
"' does not exist");
357 py::keep_alive<0, 1>())
361 py::keep_alive<0, 1>())
365 py::keep_alive<0, 1>());
370 explicit IntPairs(std::vector<std::pair<int, int>>
data) : data_(std::move(
data)) {}
371 const std::pair<int, int> *begin()
const {
return data_.data(); }
373 const std::pair<int, int> *
end()
const {
return data_.data() + data_.size(); }
376 std::vector<std::pair<int, int>> data_;
378 py::class_<IntPairs>(
m,
"IntPairs")
379 .def(
py::init<std::vector<std::pair<int, int>>>())
382 [](
const IntPairs &s) {
386 py::keep_alive<0, 1>())
389 [](
const IntPairs &s) {
393 py::keep_alive<0, 1>())
396 [](
const IntPairs &s) {
400 py::keep_alive<0, 1>())
405 [](
const IntPairs &s) {
409 py::keep_alive<0, 1>())
412 [](
const IntPairs &s) {
416 py::keep_alive<0, 1>())
419 [](
const IntPairs &s) {
423 py::keep_alive<0, 1>())
429 py::keep_alive<0, 1>())
433 py::keep_alive<0, 1>())
437 py::keep_alive<0, 1>())
443 "_make_iterator_extras",
445 py::keep_alive<0, 1>())
449 py::keep_alive<0, 1>())
451 "_make_value_extras",
453 py::keep_alive<0, 1>());
456 py::class_<NonCopyableInt>(
m,
"NonCopyableInt")
457 .def(py::init<int>())
460 py::class_<std::vector<NonCopyableInt>>(
m,
"VectorNonCopyableInt")
463 [](std::vector<NonCopyableInt> &vec,
int value) { vec.emplace_back(value); })
464 .def(
"__iter__", [](std::vector<NonCopyableInt> &vec) {
467 py::class_<std::vector<NonCopyableIntPair>>(
m,
"VectorNonCopyableIntPair")
470 [](std::vector<NonCopyableIntPair> &vec,
const std::pair<int, int> &value) {
474 [](std::vector<NonCopyableIntPair> &vec) {
477 .def(
"values", [](std::vector<NonCopyableIntPair> &vec) {
486 struct PySequenceIterator {
490 if (index == seq.size())
491 throw py::stop_iteration();
500 py::class_<PySequenceIterator>(
seq,
"Iterator")
501 .def(
"__iter__", [](PySequenceIterator &it) -> PySequenceIterator& {
return it; })
502 .def(
"__next__", &PySequenceIterator::next);
505 .def(
"__iter__", [](py::object s) {
return PySequenceIterator(s.cast<
const Sequence &>(), s); })
509 m.def(
"object_to_list", [](
const py::object &o) {
511 for (auto item : o) {
517 m.def(
"iterator_to_list", [](py::iterator it) {
519 while (it != py::iterator::sentinel()) {
527 m.def(
"sequence_length", [](
const py::sequence &
seq) {
return seq.size(); });
530 m.def(
"count_none", [](
const py::object &o) {
531 return std::count_if(o.begin(), o.end(), [](py::handle
h) {
return h.is_none(); });
534 m.def(
"find_none", [](
const py::object &o) {
535 auto it = std::find_if(o.begin(), o.end(), [](py::handle
h) {
return h.is_none(); });
536 return it->is_none();
539 m.def(
"count_nonzeros", [](
const py::dict &
d) {
540 return std::count_if(
d.begin(),
d.end(), [](std::pair<py::handle, py::handle>
p) {
541 return p.second.cast<
int>() != 0;
545 m.def(
"tuple_iterator", &test_random_access_iterator<py::tuple>);
546 m.def(
"list_iterator", &test_random_access_iterator<py::list>);
547 m.def(
"sequence_iterator", &test_random_access_iterator<py::sequence>);
551 m.def(
"iterator_passthrough", [](py::iterator
s) -> py::iterator {
557 static std::vector<int> list = {1, 2, 3};
558 m.def(
"make_iterator_1",
559 []() {
return py::make_iterator<py::return_value_policy::copy>(list); });
560 m.def(
"make_iterator_2",
561 []() {
return py::make_iterator<py::return_value_policy::automatic>(list); });
const gtsam::Symbol key('X', 0)
def step(data, isam, result, truth, currPoseIndex)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator!=(const bfloat16 &a, const bfloat16 &b)
void print_destroyed(T *inst, Values &&...values)
void print_copy_assigned(T *inst, Values &&...values)
void print_copy_created(T *inst, Values &&...values)
NonRefIterator(const T *ptr)
PYBIND11_MAKE_OPAQUE(std::vector< NonCopyableInt >)
static const Line3 l(Rot3(), 1, 1)
std::map< double, double > Sequence
Our sequence representation is a map of {x: y} values where y = f(x)
NonCopyableInt & operator=(NonCopyableInt &&other) noexcept
void print_move_assigned(T *inst, Values &&...values)
Array< int, Dynamic, 1 > v
Eigen::Triplet< double > T
py::list test_random_access_iterator(PythonType x)
NonCopyableInt(NonCopyableInt &&other) noexcept
void set(Container &c, Position position, const Value &value)
Reference counting helper.
NonZeroIterator & operator++()
NonCopyableInt(int value)
NonZeroIterator(const T *ptr)
const T & operator*() const
internal::enable_if<!(symbolic::is_symbolic< FirstType >::value||symbolic::is_symbolic< LastType >::value), ArithmeticSequence< typename internal::cleanup_index_type< FirstType >::type, Index > >::type seq(FirstType f, LastType l)
NonRefIterator & operator++()
bool operator==(const NonRefIterator &other) const
bool operator==(const NonZeroIterator< std::pair< A, B >> &it, const NonZeroSentinel &)
void print_created(T *inst, Values &&...values)
detail::initimpl::constructor< Args... > init()
Binds an existing constructor taking arguments Args...
static EIGEN_DEPRECATED const end_t end
iterator make_key_iterator(Iterator &&first, Sentinel &&last, Extra &&...extra)
iterator make_iterator(Iterator &&first, Sentinel &&last, Extra &&...extra)
Makes a python iterator from a first and past-the-end C++ InputIterator.
std::pair< NonCopyableInt, NonCopyableInt > NonCopyableIntPair
iterator make_value_iterator(Iterator &&first, Sentinel &&last, Extra &&...extra)
void print_move_created(T *inst, Values &&...values)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
TEST_SUBMODULE(sequences_and_iterators, m)