From 2ac3893d451edc178a6fcfb5ea137279570125a1 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Thu, 27 Apr 2023 23:30:31 +0200 Subject: [PATCH] more fixes for bindings --- .../include/mrpt/poses/CPose3DGridTemplate.h | 16 +-- .../include/mrpt/slam/CMetricMapBuilder.h | 11 +- .../src/slam/CMonteCarloLocalization2D.cpp | 3 +- .../src/slam/CMonteCarloLocalization3D.cpp | 3 +- libs/slam/src/slam/CMultiMetricMapPDF.cpp | 3 +- .../slam/src/slam/CMultiMetricMapPDF_RBPF.cpp | 3 +- .../mrpt => src}/slam/PF_aux_structs.h | 1 - libs/vision/include/mrpt/vision/utils.h | 53 +-------- libs/vision/src/vision_utils.cpp | 40 +------ python/.clang-format | 2 +- python/CMakeLists.txt | 3 + python/all_wrapped_mrpt_headers.hpp | 1 - python/patch-001.diff | 10 -- python/patch-002.diff | 10 -- python/patch-004.diff | 11 -- python/patch-005.diff | 12 -- python/patch-006.diff | 10 ++ python/python.conf | 106 +++++++++++------ python/stl_binders.hpp | 107 ++++++++++++++++++ 19 files changed, 219 insertions(+), 186 deletions(-) rename libs/slam/{include/mrpt => src}/slam/PF_aux_structs.h (99%) delete mode 100644 python/patch-001.diff delete mode 100644 python/patch-002.diff delete mode 100644 python/patch-004.diff delete mode 100644 python/patch-005.diff create mode 100644 python/patch-006.diff create mode 100644 python/stl_binders.hpp diff --git a/libs/poses/include/mrpt/poses/CPose3DGridTemplate.h b/libs/poses/include/mrpt/poses/CPose3DGridTemplate.h index 2308905e98..04e0011382 100644 --- a/libs/poses/include/mrpt/poses/CPose3DGridTemplate.h +++ b/libs/poses/include/mrpt/poses/CPose3DGridTemplate.h @@ -285,14 +285,14 @@ class CPose3DGridTemplate v = val; } - auto getSizeX() const { return m_sizeX; } - auto getSizeY() const { return m_sizeY; } - auto getSizeZ() const { return m_sizeZ; } - auto getSizeYaw() const { return m_sizeYaw; } - auto getSizePitch() const { return m_sizePitch; } - auto getSizeRoll() const { return m_sizeRoll; } - - auto getTotalVoxelCount() const { return m_size_xyzYPR; } + uint32_t getSizeX() const { return m_sizeX; } + uint32_t getSizeY() const { return m_sizeY; } + uint32_t getSizeZ() const { return m_sizeZ; } + uint32_t getSizeYaw() const { return m_sizeYaw; } + uint32_t getSizePitch() const { return m_sizePitch; } + uint32_t getSizeRoll() const { return m_sizeRoll; } + + uint32_t getTotalVoxelCount() const { return m_size_xyzYPR; } const std::vector& getData() const { return m_data; } std::vector& getData() { return m_data; } diff --git a/libs/slam/include/mrpt/slam/CMetricMapBuilder.h b/libs/slam/include/mrpt/slam/CMetricMapBuilder.h index 474787272e..09c746949e 100644 --- a/libs/slam/include/mrpt/slam/CMetricMapBuilder.h +++ b/libs/slam/include/mrpt/slam/CMetricMapBuilder.h @@ -113,18 +113,17 @@ class CMetricMapBuilder : public mrpt::system::COutputLogger struct TOptions { TOptions(mrpt::system::VerbosityLevel& verb_level_ref) - : verbosity_level(verb_level_ref), - enableMapUpdating(true), - debugForceInsertion(false), - alwaysInsertByClass() + : verbosity_level(verb_level_ref) { } mrpt::system::VerbosityLevel& verbosity_level; + /** Enable map updating, default is true. */ - bool enableMapUpdating; + bool enableMapUpdating = true; + /** Always insert into map. Default is false: detect if necesary. */ - bool debugForceInsertion; + bool debugForceInsertion = false; /** A list of observation classes (derived from mrpt::obs::CObservation) * which will be always inserted in the map, disregarding the minimum diff --git a/libs/slam/src/slam/CMonteCarloLocalization2D.cpp b/libs/slam/src/slam/CMonteCarloLocalization2D.cpp index bb3d86162a..86c8ae8e37 100644 --- a/libs/slam/src/slam/CMonteCarloLocalization2D.cpp +++ b/libs/slam/src/slam/CMonteCarloLocalization2D.cpp @@ -14,9 +14,10 @@ #include #include #include -#include #include +#include "PF_aux_structs.h" + using namespace mrpt; using namespace mrpt::bayes; using namespace mrpt::poses; diff --git a/libs/slam/src/slam/CMonteCarloLocalization3D.cpp b/libs/slam/src/slam/CMonteCarloLocalization3D.cpp index 31b3ac805b..4afcbd624a 100644 --- a/libs/slam/src/slam/CMonteCarloLocalization3D.cpp +++ b/libs/slam/src/slam/CMonteCarloLocalization3D.cpp @@ -13,7 +13,8 @@ #include #include #include -#include + +#include "PF_aux_structs.h" using namespace std; using namespace mrpt; diff --git a/libs/slam/src/slam/CMultiMetricMapPDF.cpp b/libs/slam/src/slam/CMultiMetricMapPDF.cpp index 21b910914c..06ac8db27a 100644 --- a/libs/slam/src/slam/CMultiMetricMapPDF.cpp +++ b/libs/slam/src/slam/CMultiMetricMapPDF.cpp @@ -22,10 +22,11 @@ #include #include #include -#include #include #include +#include "PF_aux_structs.h" + using namespace mrpt; using namespace mrpt::math; using namespace mrpt::slam; diff --git a/libs/slam/src/slam/CMultiMetricMapPDF_RBPF.cpp b/libs/slam/src/slam/CMultiMetricMapPDF_RBPF.cpp index 71072de124..d9d3135544 100644 --- a/libs/slam/src/slam/CMultiMetricMapPDF_RBPF.cpp +++ b/libs/slam/src/slam/CMultiMetricMapPDF_RBPF.cpp @@ -23,9 +23,10 @@ #include #include #include -#include #include +#include "PF_aux_structs.h" + using namespace mrpt; using namespace mrpt::bayes; using namespace mrpt::math; diff --git a/libs/slam/include/mrpt/slam/PF_aux_structs.h b/libs/slam/src/slam/PF_aux_structs.h similarity index 99% rename from libs/slam/include/mrpt/slam/PF_aux_structs.h rename to libs/slam/src/slam/PF_aux_structs.h index d0eb4118d8..cef01f5854 100644 --- a/libs/slam/include/mrpt/slam/PF_aux_structs.h +++ b/libs/slam/src/slam/PF_aux_structs.h @@ -15,7 +15,6 @@ namespace mrpt::slam::detail { using namespace mrpt; -using namespace mrpt::math; using namespace std; /** Auxiliary structure used in KLD-sampling in particle filters \sa diff --git a/libs/vision/include/mrpt/vision/utils.h b/libs/vision/include/mrpt/vision/utils.h index 64bbb3ae7a..768167653a 100644 --- a/libs/vision/include/mrpt/vision/utils.h +++ b/libs/vision/include/mrpt/vision/utils.h @@ -71,7 +71,7 @@ void openCV_cross_correlation( * image. * \param A [IN] The 3x3 intrinsic parameters matrix for the camera. * \return The mrpt::math::TPoint3D containing the output unitary vector. - * \sa buildIntrinsicParamsMatrix, defaultIntrinsicParamsMatrix, TPixelCoordf + * \sa buildIntrinsicParamsMatrix, TPixelCoordf */ mrpt::math::TPoint3D pixelTo3D( const mrpt::img::TPixelCoordf& xy, const mrpt::math::CMatrixDouble33& A); @@ -90,61 +90,12 @@ mrpt::math::TPoint3D pixelTo3D( * See also the tutorial discussing the camera model parameters. - * \sa defaultIntrinsicParamsMatrix, pixelTo3D + * \sa pixelTo3D */ mrpt::math::CMatrixDouble33 buildIntrinsicParamsMatrix( const double focalLengthX, const double focalLengthY, const double centerX, const double centerY); -/** Returns the stored, default intrinsic params matrix for a given camera: - * \param camIndex [IN] Posible values are listed next. - * \param resolutionX [IN] The number of pixel columns - * \param resolutionY [IN] The number of pixel rows - * - * The matrix is generated for the indicated camera resolution configuration. - * The following table summarizes the current supported cameras and the values - as - * ratios of the corresponding horz. or vert. resolution:
- -
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
camIndex
Manufacturer
Camera model
fx
fy
cx
cy
0
Point Grey Research
Bumblebee
0.79345
1.05793
0.55662
0.52692
1
Sony
???
0.95666094
1.3983423f
0.54626328f
0.4939191f
-
- - * \sa buildIntrinsicParamsMatrix, pixelTo3D - */ -mrpt::math::CMatrixDouble33 defaultIntrinsicParamsMatrix( - unsigned int camIndex = 0, unsigned int resolutionX = 320, - unsigned int resolutionY = 240); - /** Computes the mean squared distance between a set of 3D correspondences * ... */ diff --git a/libs/vision/src/vision_utils.cpp b/libs/vision/src/vision_utils.cpp index f815e3b674..915256f894 100644 --- a/libs/vision/src/vision_utils.cpp +++ b/libs/vision/src/vision_utils.cpp @@ -168,43 +168,6 @@ CMatrixDouble33 vision::buildIntrinsicParamsMatrix( return A; } -/*------------------------------------------------------------- - defaultIntrinsicParamsMatrix --------------------------------------------------------------*/ -CMatrixDouble33 vision::defaultIntrinsicParamsMatrix( - unsigned int camIndex, unsigned int resX, unsigned int resY) -{ - float fx, fy, cx, cy; - - switch (camIndex) - { - case 0: - // Bumblebee: - fx = 0.79345f; - fy = 1.05793f; - cx = 0.55662f; - cy = 0.52692f; - break; - - case 1: - // Sony: - fx = 0.95666094f; - fy = 1.3983423f; - cx = 0.54626328f; - cy = 0.4939191f; - break; - - default: - { - THROW_EXCEPTION_FMT( - "Unknown camera index!! for 'camIndex'=%u", camIndex); - } - } - - return buildIntrinsicParamsMatrix( - resX * fx, resY * fy, resX * cx, resY * cy); -} - /*------------------------------------------------------------- computeMsd -------------------------------------------------------------*/ @@ -1893,9 +1856,8 @@ void vision::computeStereoRectificationMaps( } // end computeStereoRectificationMaps TStereoSystemParams::TStereoSystemParams() - { - K = defaultIntrinsicParamsMatrix(0, 640, 480); + // K = defaultIntrinsicParamsMatrix(0, 640, 480); F.setZero(); F(1, 2) = -1; F(2, 1) = 1; diff --git a/python/.clang-format b/python/.clang-format index 445f63ed30..7968b43c1d 100644 --- a/python/.clang-format +++ b/python/.clang-format @@ -1,3 +1,3 @@ DisableFormat: true -SortIncludes: Never +SortIncludes: false diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 7ca7209b01..5217b4994a 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -31,6 +31,9 @@ target_link_libraries(pymrpt PUBLIC mrpt::gui mrpt::nav ) + +target_include_directories(pymrpt PRIVATE ".") + target_compile_definitions(pymrpt PRIVATE PYBIND11_MAJOR_VERSION=${PYBIND11_MAJOR_VERSION} PYBIND11_MINOR_VERSION=${PYBIND11_MINOR_VERSION} diff --git a/python/all_wrapped_mrpt_headers.hpp b/python/all_wrapped_mrpt_headers.hpp index e463ca11c5..93b799901d 100644 --- a/python/all_wrapped_mrpt_headers.hpp +++ b/python/all_wrapped_mrpt_headers.hpp @@ -414,7 +414,6 @@ #include #include #include -#include #include #include #include diff --git a/python/patch-001.diff b/python/patch-001.diff deleted file mode 100644 index 95ebe87c4d..0000000000 --- a/python/patch-001.diff +++ /dev/null @@ -1,10 +0,0 @@ ---- generated-sources-pybind/mrpt/maps/COctoMapBase.cpp 2023-04-27 00:54:44.080520471 +0200 -+++ generated-sources-pybind/mrpt/maps/COctoMapBase.new.cpp 2023-04-27 01:00:54.078049124 +0200 -@@ -1,3 +1,7 @@ -+#include -+#include -+#include -+ - #include - #include - #include diff --git a/python/patch-002.diff b/python/patch-002.diff deleted file mode 100644 index 98e636caf9..0000000000 --- a/python/patch-002.diff +++ /dev/null @@ -1,10 +0,0 @@ ---- generated-sources-pybind/mrpt/maps/COctoMapBase_1.cpp 2023-04-27 00:54:44.080520471 +0200 -+++ generated-sources-pybind/mrpt/maps/COctoMapBase_1.new.cpp 2023-04-27 01:00:54.078049124 +0200 -@@ -1,3 +1,7 @@ -+#include -+#include -+#include -+ - #include - #include - #include diff --git a/python/patch-004.diff b/python/patch-004.diff deleted file mode 100644 index 8e12cf030c..0000000000 --- a/python/patch-004.diff +++ /dev/null @@ -1,11 +0,0 @@ ---- generated-sources-pybind/mrpt/nav/reactive/CLogFileRecord.cpp 2023-04-27 22:22:25.333158055 +0200 -+++ generated-sources-pybind/mrpt/nav/reactive/CLogFileRecord.cpp.new.cpp 2023-04-27 22:34:14.515135791 +0200 -@@ -23,6 +23,8 @@ - #include - #include - -+#include -+ - - #ifndef BINDER_PYBIND11_TYPE_CASTER - #define BINDER_PYBIND11_TYPE_CASTER diff --git a/python/patch-005.diff b/python/patch-005.diff deleted file mode 100644 index 32e3007dc9..0000000000 --- a/python/patch-005.diff +++ /dev/null @@ -1,12 +0,0 @@ ---- generated-sources-pybind/mrpt/obs/gnss_messages_type_list.cpp 2023-04-27 22:41:46.499949717 +0200 -+++ generated-sources-pybind/mrpt/obs/gnss_messages_type_list.new.cpp 2023-04-27 22:41:37.404072257 +0200 -@@ -21,6 +21,9 @@ - #include - #include - -+#include -+ -+ - #ifndef BINDER_PYBIND11_TYPE_CASTER - #define BINDER_PYBIND11_TYPE_CASTER - PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) diff --git a/python/patch-006.diff b/python/patch-006.diff new file mode 100644 index 0000000000..196e83229b --- /dev/null +++ b/python/patch-006.diff @@ -0,0 +1,10 @@ +--- generated-sources-pybind/mrpt/serialization/CArchive_1.cpp 2023-04-27 23:31:05.248357920 +0200 ++++ generated-sources-pybind/mrpt/serialization/CArchive_1.new.cpp 2023-04-27 23:38:49.302474957 +0200 +@@ -15,6 +15,7 @@ + #include + #include + ++#include + + #ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER diff --git a/python/python.conf b/python/python.conf index ff2f8de23d..3250798363 100644 --- a/python/python.conf +++ b/python/python.conf @@ -14,13 +14,19 @@ # --------------------------------------------------------------- # Except externals: # --------------------------------------------------------------- --namespace nanoflann -namespace Eigen +-namespace nanoflann # # --------------------------------------------------------------- # Plus STL: # --------------------------------------------------------------- -+include ++binder std::map binder::map_binder ++binder std::vector binder::vector_binder ++binder std::deque binder::deque_binder +#+include # See https://github.com/RosettaCommons/binder/issues/100#issuecomment-867197266 ++include +# +-include # # --------------------------------------------------------------- # Minimize STL instances: @@ -30,18 +36,29 @@ -class std::any -class std::basic_ios -class std::basic_iostream +-class std::basic_istringstream -class std::basic_streambuf -class std::basic_string_view -class std::exception -class std::fpos -class std::ios_base +-class std::istream +-class std::iterator +-class std::reverse_iterator +-class std::ostream -class std::stringstream -class std::type_info -class std::vector -class tm -namespace std::chrono --class std::basic_istringstream +class std::vector +-class std::runtime_error +-class std::array +-class std::weak_ptr +# +# Note: this removes many interesting MRPT API functions. Consider +# porting them to the output raw pointer convention just for the wrapper. +-class std::optional # # --------------------------------------------------------------- # Remove problematic parts: @@ -50,13 +67,28 @@ -class mrpt::containers::NonCopiableData -class mrpt::containers::PerThreadDataHolder -class mrpt::containers::vector_with_small_size_optimization +-class mrpt::ExceptionWithCallBack +-class mrpt::ExceptionWithCallBackBase -class mrpt::io::CPipe +-class mrpt::math::CMatrixDynamic +-class mrpt::math::CMatrixDynamic> +-class mrpt::maps::TMetricMapInitializer +-class mrpt::nav::CAbstractNavigator::TNavigationParams -class mrpt::nav::CPTG_DiffDrive_CollisionGridBased::TCellForLambdaFunction +-class mrpt::opengl::COctreePointRenderer +-class mrpt::opengl::CRenderizable::RenderContext -class mrpt::opengl::FrameBuffer::RAII_Impl +-class mrpt::opengl::Program +-class mrpt::opengl::Shader -class mrpt::opengl::Shader -class mrpt::opengl::Viewport::PerThreadData -class mrpt::system::COutputLogger -class mrpt::system::CTimeLogger::TCallData +-class mrpt::typemeta::TEnumTypeFiller +-class mrpt::typemeta::TTypeName +-class nanogui::Object +-class nanogui::Theme +-class nanogui::Widget -class std::mutex -class std::recursive_mutex -class std::vector @@ -67,64 +99,74 @@ -field mrpt::hwdrivers::CGPS_NTRIP::gps -field mrpt::hwdrivers::CGPS_NTRIP::ntrip -field mrpt::hwdrivers::CNTRIPClient::stream_data +-field mrpt::slam::CMetricMapBuilder::options +-function mrpt::demangle -function mrpt::format -function mrpt::io::CFileStream::printf -function mrpt::io::CStream::printf +-function mrpt::maps::CPointsMap::getPointsBuffer +-function mrpt::math::internalAssertEigenDefined +-function mrpt::math::MatrixBase::blockCopy -function mrpt::math::MatrixBase::col +-function mrpt::math::MatrixBase::extractMatrix -function mrpt::math::MatrixBase::row -function mrpt::math::MatrixVectorBase::array -function mrpt::math::MatrixVectorBase::block +-function mrpt::math::MatrixVectorBase::dot +-function mrpt::math::MatrixVectorBase::matProductOf_Ab +-function mrpt::math::MatrixVectorBase::matProductOf_Atb -function mrpt::math::MatrixVectorBase::operator- -function mrpt::math::MatrixVectorBase::operator* -function mrpt::math::MatrixVectorBase::transpose +-function mrpt::obs::CActionCollection::getActionByClass +-function mrpt::system::os::sprintf -function std::optional::operator-> -function std::optional::operator* -function std::optional::value -namespace mrpt::containers::internal --function mrpt::maps::CPointsMap::getPointsBuffer --class mrpt::math::CMatrixDynamic --class mrpt::math::CMatrixDynamic> --function mrpt::math::MatrixBase::blockCopy --function mrpt::math::MatrixBase::extractMatrix --function mrpt::math::MatrixVectorBase::dot --function mrpt::math::MatrixVectorBase::matProductOf_Ab --function mrpt::math::MatrixVectorBase::matProductOf_Atb --function mrpt::math::internalAssertEigenDefined --namespace mrpt::internal -namespace mrpt::cpu::internal -namespace mrpt::gui::internal +-namespace mrpt::internal -namespace mrpt::io::internal +-namespace mrpt::literals -namespace mrpt::math::internal -namespace mrpt::opengl::internal --class mrpt::nav::CAbstractNavigator::TNavigationParams --function mrpt::obs::CActionCollection::getActionByClass --class mrpt::opengl::Shader --class mrpt::opengl::CRenderizable::RenderContext +-namespace mrpt::slam::detail +# +# Missing includes +# ++include_for_namespace mrpt::obs::gnss ++include_for_class mrpt::maps::COctoMapBase ++include_for_class mrpt::maps::COctoMapBase ++include_for_class mrpt::maps::COctoMapBase ++include_for_class mrpt::maps::COctoMapBase ++include_for_class mrpt::nav::CLogFileRecord ++include_for_class mrpt::serialization::CArchive # # --------------------------------------------------------------- # Redundant instantiations # --------------------------------------------------------------- --class mrpt::math::MatrixBase> -class mrpt::math::MatrixBase> --class mrpt::math::MatrixVectorBase> --class mrpt::math::MatrixVectorBase> +-class mrpt::math::MatrixBase> -class mrpt::math::MatrixBase> +-class mrpt::math::MatrixBase> -class mrpt::math::MatrixBase> --class mrpt::math::MatrixBase> +-class mrpt::math::MatrixBase> +-class mrpt::math::MatrixBase> +-class mrpt::math::MatrixBase> -class mrpt::math::MatrixBase> --class mrpt::math::MatrixBase> +-class mrpt::math::MatrixBase> +-class mrpt::math::MatrixBase> -class mrpt::math::MatrixBase> +-class mrpt::math::MatrixBase> -class mrpt::math::MatrixBase> --class mrpt::math::MatrixBase> --class mrpt::math::MatrixBase> --class mrpt::math::MatrixBase> --class mrpt::math::MatrixBase> +-class mrpt::math::MatrixBase> +-class mrpt::math::MatrixBase> +-class mrpt::math::MatrixBase> -class mrpt::math::MatrixBase> --class mrpt::math::MatrixBase> +-class mrpt::math::MatrixBase> -class mrpt::math::MatrixBase> --class mrpt::math::MatrixBase> --class mrpt::math::MatrixBase> +-class mrpt::math::MatrixBase> -class mrpt::math::MatrixBase> --class mrpt::math::MatrixBase> --class mrpt::math::MatrixBase> --class mrpt::math::MatrixBase> +-class mrpt::math::MatrixVectorBase> +-class mrpt::math::MatrixVectorBase> diff --git a/python/stl_binders.hpp b/python/stl_binders.hpp new file mode 100644 index 0000000000..d88656710b --- /dev/null +++ b/python/stl_binders.hpp @@ -0,0 +1,107 @@ +// -*- mode:c++;tab-width:2;indent-tabs-mode:t;show-trailing-whitespace:t;rm-trailing-spaces:t -*- +// vi: set ts=2 noet: +// +// Copyright (c) 2016 Sergey Lyskov +// +// All rights reserved. Use of this source code is governed by a +// MIT license that can be found in the LICENSE file. + +/// @file binder/std_binders.hpp +/// @brief Support for custom binders for some std:: template classes +/// @author Sergey Lyskov + + +#ifndef _INCLUDED_std_binders_hpp_ +#define _INCLUDED_std_binders_hpp_ + +#include +#include +#include + +namespace binder { + +template class vector_binder +{ + using Vector = std::vector; + using SizeType = typename Vector::size_type; + + using Class_ = pybind11::class_ >; + + +public: + vector_binder(pybind11::module &m, std::string const &name, std::string const & /*allocator name*/) + { + using Vector = std::vector; + using holder_type = std::shared_ptr>; + using Class_ = pybind11::class_; + + Class_ cl = pybind11::bind_vector(m, "vector_" + name); + + // cl.def(pybind11::init()); + // cl.def("resize", (void (Vector::*) (size_type count)) & Vector::resize, "changes the number of elements stored"); + + cl.def("empty", &Vector::empty, "checks whether the container is empty"); + cl.def("max_size", &Vector::max_size, "returns the maximum possible number of elements"); + cl.def("reserve", &Vector::reserve, "reserves storage"); + cl.def("capacity", &Vector::capacity, "returns the number of elements that can be held in currently allocated storage"); + cl.def("shrink_to_fit", &Vector::shrink_to_fit, "reduces memory usage by freeing unused memory"); + cl.def("clear", &Vector::clear, "clears the contents"); + cl.def("swap", (void(Vector::*)(Vector &)) & Vector::swap, "swaps the contents"); + + + + // cl.def("front", [](Vector &v) { + // if (v.size()) return v.front(); + // else throw pybind11::index_error(); + // }, "access the first element"); + // cl.def("back", [](Vector &v) { + // if (v.size()) return v.back(); + // else throw pybind11::index_error(); + // }, "access the last element "); + } +}; + + +template class map_binder +{ +public: + map_binder(pybind11::module &m, std::string const &key_name, std::string const &value_name, std::string const & /*compare name*/, std::string const & /*allocator name*/) + { + using Map = std::map; + using holder_type = std::shared_ptr< std::map >; + using Class_ = pybind11::class_; + + Class_ cl = pybind11::bind_map(m, "map_" + key_name + '_' + value_name); + } +}; + +template class deque_binder +{ + using Vector = std::deque; + using SizeType = typename Vector::size_type; + + using Class_ = pybind11::class_ >; + + +public: + deque_binder(pybind11::module &m, std::string const &name, std::string const & /*allocator name*/) + { + using Vector = std::deque; + using holder_type = std::shared_ptr>; + using Class_ = pybind11::class_; + + Class_ cl = pybind11::bind_vector(m, "deque_" + name); + + // cl.def(pybind11::init()); + // cl.def("resize", (void (Vector::*) (size_type count)) & Vector::resize, "changes the number of elements stored"); + + cl.def("empty", &Vector::empty, "checks whether the container is empty"); + cl.def("clear", &Vector::clear, "clears the contents"); + cl.def("swap", (void(Vector::*)(Vector &)) & Vector::swap, "swaps the contents"); + } +}; + + +} // namespace binder + +#endif // _INCLUDED_std_binders_hpp_