mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
Python3 compatibility
This commit is contained in:
parent
c97b462024
commit
b2adcf0247
@ -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()))
|
if (!moveit::python::convertible(src, ros::message_traits::DataType<T>::value()))
|
||||||
return false;
|
return false;
|
||||||
// serialize src into (python) buffer
|
// serialize src into (python) buffer
|
||||||
object pstream = module::import("StringIO").attr("StringIO")();
|
object pstream = module::import("io").attr("BytesIO")();
|
||||||
src.attr("serialize")(pstream);
|
src.attr("serialize")(pstream);
|
||||||
object pbuffer = pstream.attr("getvalue")();
|
object pbuffer = pstream.attr("getvalue")();
|
||||||
// deserialize C++ type from buffer
|
// deserialize C++ type from buffer
|
||||||
|
|||||||
@ -1,4 +1,4 @@
|
|||||||
<package format="2">
|
<package format="3">
|
||||||
<name>moveit_task_constructor_core</name>
|
<name>moveit_task_constructor_core</name>
|
||||||
<version>0.0.0</version>
|
<version>0.0.0</version>
|
||||||
<description>MoveIt Task Pipeline</description>
|
<description>MoveIt Task Pipeline</description>
|
||||||
@ -8,6 +8,8 @@
|
|||||||
<maintainer email="rhaschke@techfak.uni-bielefeld.de">Robert Haschke</maintainer>
|
<maintainer email="rhaschke@techfak.uni-bielefeld.de">Robert Haschke</maintainer>
|
||||||
|
|
||||||
<buildtool_depend>catkin</buildtool_depend>
|
<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>eigen_conversions</depend>
|
||||||
<depend>geometry_msgs</depend>
|
<depend>geometry_msgs</depend>
|
||||||
|
|||||||
@ -1 +1 @@
|
|||||||
from _python_tools import *
|
from ._python_tools import *
|
||||||
|
|||||||
@ -1,2 +0,0 @@
|
|||||||
from core import *
|
|
||||||
import stages
|
|
||||||
@ -1 +1 @@
|
|||||||
from _core import *
|
from ._core import *
|
||||||
|
|||||||
@ -1 +1,2 @@
|
|||||||
from _stages import *
|
from ._core import Stage
|
||||||
|
from ._stages import *
|
||||||
|
|||||||
@ -1,6 +1,6 @@
|
|||||||
#! /usr/bin/env python
|
#! /usr/bin/env python
|
||||||
# -*- coding: utf-8 -*-
|
|
||||||
|
|
||||||
|
from __future__ import print_function
|
||||||
import unittest
|
import unittest
|
||||||
import rostest
|
import rostest
|
||||||
from moveit.python_tools import roscpp_init
|
from moveit.python_tools import roscpp_init
|
||||||
@ -36,7 +36,7 @@ class Test(unittest.TestCase):
|
|||||||
|
|
||||||
self.assertEqual(len(task.solutions), 1)
|
self.assertEqual(len(task.solutions), 1)
|
||||||
for s in task.solutions:
|
for s in task.solutions:
|
||||||
print s
|
print(s)
|
||||||
s = task.solutions[0]
|
s = task.solutions[0]
|
||||||
task.execute(s)
|
task.execute(s)
|
||||||
|
|
||||||
@ -66,8 +66,6 @@ class Test(unittest.TestCase):
|
|||||||
if task.plan():
|
if task.plan():
|
||||||
task.publish(task.solutions[0])
|
task.publish(task.solutions[0])
|
||||||
|
|
||||||
rospy.sleep(100)
|
|
||||||
|
|
||||||
|
|
||||||
if __name__ == '__main__':
|
if __name__ == '__main__':
|
||||||
roscpp_init("test_mtc")
|
roscpp_init("test_mtc")
|
||||||
|
|||||||
@ -46,7 +46,7 @@ void setForwardedProperties(Stage& self, const py::object& names) {
|
|||||||
std::set<std::string> s;
|
std::set<std::string> s;
|
||||||
try {
|
try {
|
||||||
// handle string argument as single name
|
// handle string argument as single name
|
||||||
if (PyString_Check(names.ptr()))
|
if (PyBytes_Check(names.ptr()))
|
||||||
s.emplace(names.cast<std::string>());
|
s.emplace(names.cast<std::string>());
|
||||||
else // expect iterable otherwise
|
else // expect iterable otherwise
|
||||||
for (auto item : names)
|
for (auto item : names)
|
||||||
|
|||||||
@ -94,12 +94,21 @@ boost::any PropertyConverterRegistry::fromPython(const py::object& po) {
|
|||||||
|
|
||||||
if (PyBool_Check(o))
|
if (PyBool_Check(o))
|
||||||
return (o == Py_True);
|
return (o == Py_True);
|
||||||
|
#if PY_MAJOR_VERSION >= 3
|
||||||
|
if (PyLong_Check(o))
|
||||||
|
return PyLong_AS_LONG(o);
|
||||||
|
#else
|
||||||
if (PyInt_Check(o))
|
if (PyInt_Check(o))
|
||||||
return PyInt_AS_LONG(o);
|
return PyInt_AS_LONG(o);
|
||||||
|
#endif
|
||||||
if (PyFloat_Check(o))
|
if (PyFloat_Check(o))
|
||||||
return PyFloat_AS_DOUBLE(o);
|
return PyFloat_AS_DOUBLE(o);
|
||||||
|
#if PY_MAJOR_VERSION >= 3
|
||||||
|
if (PyUnicode_Check(o))
|
||||||
|
#else
|
||||||
if (PyString_Check(o))
|
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);
|
const std::string& ros_msg_name = rosMsgName(o);
|
||||||
auto it = registry_singleton_.msg_names_.find(ros_msg_name);
|
auto it = registry_singleton_.msg_names_.find(ros_msg_name);
|
||||||
|
|||||||
@ -18,7 +18,7 @@ py::object createMessage(const std::string& ros_msg_name) {
|
|||||||
bool convertible(const pybind11::handle& h, const char* ros_msg_name) {
|
bool convertible(const pybind11::handle& h, const char* ros_msg_name) {
|
||||||
try {
|
try {
|
||||||
PyObject* o = h.attr("_type").ptr();
|
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) {
|
} catch (const std::exception& e) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|||||||
@ -1,6 +1,6 @@
|
|||||||
#!/usr/bin/env python
|
#!/usr/bin/env python
|
||||||
|
|
||||||
from distutils.core import setup
|
from setuptools import setup
|
||||||
from catkin_pkg.python_setup import generate_distutils_setup
|
from catkin_pkg.python_setup import generate_distutils_setup
|
||||||
|
|
||||||
d = generate_distutils_setup(
|
d = generate_distutils_setup(
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user