Python3 compatibility

This commit is contained in:
Robert Haschke 2020-07-15 15:09:09 +02:00
parent c97b462024
commit b2adcf0247
11 changed files with 23 additions and 15 deletions

View File

@ -69,7 +69,7 @@ struct type_caster<T, enable_if_t<ros::message_traits::IsMessage<T>::value>>
if (!moveit::python::convertible(src, ros::message_traits::DataType<T>::value()))
return false;
// serialize src into (python) buffer
object pstream = module::import("StringIO").attr("StringIO")();
object pstream = module::import("io").attr("BytesIO")();
src.attr("serialize")(pstream);
object pbuffer = pstream.attr("getvalue")();
// deserialize C++ type from buffer

View File

@ -1,4 +1,4 @@
<package format="2">
<package format="3">
<name>moveit_task_constructor_core</name>
<version>0.0.0</version>
<description>MoveIt Task Pipeline</description>
@ -8,6 +8,8 @@
<maintainer email="rhaschke@techfak.uni-bielefeld.de">Robert Haschke</maintainer>
<buildtool_depend>catkin</buildtool_depend>
<buildtool_depend condition="$ROS_PYTHON_VERSION == 2">python-setuptools</buildtool_depend>
<buildtool_depend condition="$ROS_PYTHON_VERSION == 3">python3-setuptools</buildtool_depend>
<depend>eigen_conversions</depend>
<depend>geometry_msgs</depend>

View File

@ -1 +1 @@
from _python_tools import *
from ._python_tools import *

View File

@ -1,2 +0,0 @@
from core import *
import stages

View File

@ -1 +1 @@
from _core import *
from ._core import *

View File

@ -1 +1,2 @@
from _stages import *
from ._core import Stage
from ._stages import *

View File

@ -1,6 +1,6 @@
#! /usr/bin/env python
# -*- coding: utf-8 -*-
from __future__ import print_function
import unittest
import rostest
from moveit.python_tools import roscpp_init
@ -36,7 +36,7 @@ class Test(unittest.TestCase):
self.assertEqual(len(task.solutions), 1)
for s in task.solutions:
print s
print(s)
s = task.solutions[0]
task.execute(s)
@ -66,8 +66,6 @@ class Test(unittest.TestCase):
if task.plan():
task.publish(task.solutions[0])
rospy.sleep(100)
if __name__ == '__main__':
roscpp_init("test_mtc")

View File

@ -46,7 +46,7 @@ void setForwardedProperties(Stage& self, const py::object& names) {
std::set<std::string> s;
try {
// handle string argument as single name
if (PyString_Check(names.ptr()))
if (PyBytes_Check(names.ptr()))
s.emplace(names.cast<std::string>());
else // expect iterable otherwise
for (auto item : names)

View File

@ -94,12 +94,21 @@ boost::any PropertyConverterRegistry::fromPython(const py::object& po) {
if (PyBool_Check(o))
return (o == Py_True);
#if PY_MAJOR_VERSION >= 3
if (PyLong_Check(o))
return PyLong_AS_LONG(o);
#else
if (PyInt_Check(o))
return PyInt_AS_LONG(o);
#endif
if (PyFloat_Check(o))
return PyFloat_AS_DOUBLE(o);
#if PY_MAJOR_VERSION >= 3
if (PyUnicode_Check(o))
#else
if (PyString_Check(o))
return std::string(PyString_AS_STRING(o));
#endif
return py::cast<std::string>(o);
const std::string& ros_msg_name = rosMsgName(o);
auto it = registry_singleton_.msg_names_.find(ros_msg_name);

View File

@ -18,7 +18,7 @@ py::object createMessage(const std::string& ros_msg_name) {
bool convertible(const pybind11::handle& h, const char* ros_msg_name) {
try {
PyObject* o = h.attr("_type").ptr();
return PyString_Check(o) && strcmp(PyString_AS_STRING(o), ros_msg_name) == 0;
return py::cast<std::string>(o) == ros_msg_name;
} catch (const std::exception& e) {
return false;
}

View File

@ -1,6 +1,6 @@
#!/usr/bin/env python
from distutils.core import setup
from setuptools import setup
from catkin_pkg.python_setup import generate_distutils_setup
d = generate_distutils_setup(