Program Listing for File pybind11.hpp

Return to documentation for file (include/pinocchio/bindings/python/pybind11.hpp)

#ifndef __pinocchio_python_pybind11_hpp__
#define __pinocchio_python_pybind11_hpp__


#include <iostream>
#include <pinocchio/fwd.hpp>

// This lines forces clang-format to keep the include split here
#include <pybind11/pybind11.h>

#include <boost/python.hpp>

namespace pinocchio {
namespace python {
namespace bp = boost::python;
namespace py = pybind11;

template <typename T>
inline py::object to(T& t) {
  // Create PyObject using boost Python
  bp::object obj = bp::api::object(t);
  PyObject* pyobj = obj.ptr();
  return pybind11::reinterpret_borrow<py::object>(pyobj);
}
template <typename T>
inline py::object to(T* t) {
  // Create PyObject using boost Python
  typename bp::manage_new_object::apply<T*>::type converter;
  PyObject* pyobj = converter(t);
  // Create the Pybind11 object
  return py::reinterpret_borrow<py::object>(pyobj);
}

template <typename ReturnType>
inline ReturnType& from(py::handle model) {
  return bp::extract<ReturnType&>(model.ptr());
}

template <typename T>
struct convert_type {
  typedef T type;
  static inline T _to(T t) { return t; }
  static inline type _from(type t) { return t; }
};
template <>
struct convert_type<void> {
  // typedef void type;
  // static inline void _to() {}
};

template <typename T>
struct convert_boost_python_object {
  typedef py::object type;
  static inline type _to(T t) {
    return to<typename std::remove_pointer<typename std::remove_reference<
        typename std::remove_cv<T>::type>::type>::type>(t);
  }
  static inline T _from(type t) {
    return from<
        typename std::remove_cv<typename std::remove_reference<T>::type>::type>(
        t);
  }
};

#define PINOCCHIO_PYBIND11_ADD_CONVERT_TYPE(CLASS)                    \
  namespace pinocchio {                                               \
  namespace python {                                                  \
  template <>                                                         \
  struct convert_type<CLASS> : convert_boost_python_object<CLASS> {}; \
  }                                                                   \
  }

#define _SINGLE_ARG(...) __VA_ARGS__
#define PINOCCHIO_PYBIND11_ADD_ALL_CONVERT_TYPE(CLASS)           \
  PINOCCHIO_PYBIND11_ADD_CONVERT_TYPE(_SINGLE_ARG(CLASS))        \
  PINOCCHIO_PYBIND11_ADD_CONVERT_TYPE(_SINGLE_ARG(CLASS const))  \
  PINOCCHIO_PYBIND11_ADD_CONVERT_TYPE(_SINGLE_ARG(CLASS&))       \
  PINOCCHIO_PYBIND11_ADD_CONVERT_TYPE(_SINGLE_ARG(CLASS const&)) \
  PINOCCHIO_PYBIND11_ADD_CONVERT_TYPE(_SINGLE_ARG(CLASS*))       \
  PINOCCHIO_PYBIND11_ADD_CONVERT_TYPE(_SINGLE_ARG(CLASS const*))

namespace internal {

template <typename R, typename... Args>
auto call(R (*f)(Args...), typename convert_type<Args>::type... args) {
  return convert_type<R>::_to(f(convert_type<Args>::_from(args)...));
}
template <typename... Args>
void call(void (*f)(Args...), typename convert_type<Args>::type... args) {
  f(convert_type<Args>::_from(args)...);
}

template <typename T>
struct function_wrapper;

template <typename R, typename... Args>
struct function_wrapper<R (*)(Args...)> {
  static const size_t nargs = sizeof...(Args);

  typedef R result_type;

  template <size_t i>
  struct arg {
    typedef typename std::tuple_element<i, std::tuple<Args...>>::type type;
  };

  typedef R (*func_type)(Args...);

  func_type f;

  // typename convert_type<result_type>::type
  auto operator()(typename convert_type<Args>::type... args) {
    return call(f, args...);
  }
};
}  // namespace internal

template <typename R, typename... Args>
internal::function_wrapper<R (*)(Args...)> make_pybind11_function(
    R (*func)(Args...)) {
  internal::function_wrapper<R (*)(Args...)> wrapper;
  wrapper.f = func;
  return wrapper;
}

template <typename T>
py::object default_arg(T t) {
  py::object obj = to<T>(t);
  //obj.inc_ref();
  return obj;
}

#define PINOCCHIO_PYBIND11_TYPE_CASTER(native_type, boost_python_name)     \
  namespace pybind11 {                                                     \
  namespace detail {                                                       \
  template <>                                                              \
  struct type_caster<native_type> {                                        \
    PYBIND11_TYPE_CASTER(_SINGLE_ARG(native_type), boost_python_name);     \
                                                                           \
    /* Python -> C++ */                                                    \
    bool load(pybind11::handle src, bool) {                                \
      PyObject* source = src.ptr();                                        \
      value = boost::python::extract<native_type>(source);                 \
      return !PyErr_Occurred();                                            \
    }                                                                      \
    /* C++ -> Python */                                                    \
    static pybind11::handle cast(native_type src,                          \
                                 pybind11::return_value_policy /*policy*/, \
                                 pybind11::handle /*parent*/) {            \
      return boost::python::api::object(src).ptr();                        \
    }                                                                      \
  };                                                                       \
  } /* namespace detail */                                                 \
  } /* namespace pybind11 */

}  // namespace python
}  // namespace pinocchio

#undef _SINGLE_ARG

#endif  // #ifndef __pinocchio_python_pybind11_hpp__