Skip to content

Commit 2de1868

Browse files
Port actionlib_tools to Python 3 (#169)
Based on #168 and ros/rosdistro#25920 Fixes: #153 and #167 Signed-off-by: Mikael Arguedas <[email protected]>
1 parent 81cdea2 commit 2de1868

File tree

8 files changed

+27
-18
lines changed

8 files changed

+27
-18
lines changed

actionlib_tools/CMakeLists.txt

+4-5
Original file line numberDiff line numberDiff line change
@@ -3,12 +3,11 @@ project(actionlib_tools)
33

44
find_package(catkin REQUIRED)
55

6+
catkin_python_setup()
7+
68
catkin_package()
79

810
catkin_install_python(PROGRAMS
9-
# These scripts require Python 2 dependency wx
10-
# scripts/axclient.py
11-
# scripts/axserver.py
12-
scripts/dynamic_action.py
13-
scripts/library.py
11+
scripts/axclient.py
12+
scripts/axserver.py
1413
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})

actionlib_tools/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,6 @@
2222
<exec_depend>actionlib</exec_depend>
2323
<exec_depend>actionlib_msgs</exec_depend>
2424
<!-- Noetic uses Python 3 -->
25-
<!--<exec_depend>python-wxtools</exec_depend>-->
25+
<exec_depend>python3-wxgtk4.0</exec_depend>
2626

2727
</package>

actionlib_tools/scripts/axclient.py

+5-5
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
#! /usr/bin/python
1+
#!/usr/bin/env python3
22
# **********************************************************
33
# Software License Agreement (BSD License)
44
#
@@ -48,9 +48,9 @@
4848
import actionlib
4949
import threading
5050
import rostopic
51-
from io import StringIO
52-
from library import to_yaml, yaml_msg_str
53-
from dynamic_action import DynamicAction
51+
from io import BytesIO
52+
from actionlib_tools.library import to_yaml, yaml_msg_str
53+
from actionlib_tools.dynamic_action import DynamicAction
5454
from actionlib_msgs.msg import GoalStatus
5555

5656

@@ -102,7 +102,7 @@ def on_goal(self, event):
102102
try:
103103
self.goal_msg = yaml_msg_str(self.action_type.goal,
104104
self.goal.GetValue())
105-
buff = StringIO()
105+
buff = BytesIO()
106106
self.goal_msg.serialize(buff)
107107

108108
# send the goal to the action server and register the relevant

actionlib_tools/scripts/axserver.py

+6-6
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
#!/usr/bin/env python
1+
#!/usr/bin/env python3
22
# Software License Agreement (BSD License)
33
#
44
# Copyright (c) 2009, Willow Garage, Inc.
@@ -43,9 +43,9 @@
4343
import rospy
4444
import actionlib
4545
import threading
46-
from io import StringIO
47-
from library import to_yaml, yaml_msg_str
48-
from dynamic_action import DynamicAction
46+
from io import BytesIO
47+
from actionlib_tools.library import to_yaml, yaml_msg_str
48+
from actionlib_tools.dynamic_action import DynamicAction
4949

5050
SEND_FEEDBACK = 0
5151
SUCCEED = 1
@@ -139,7 +139,7 @@ def on_feedback(self, event):
139139
try:
140140
self.feedback_msg = yaml_msg_str(self.action_type.feedback,
141141
self.feedback.GetValue())
142-
buff = StringIO()
142+
buff = BytesIO()
143143
self.feedback_msg.serialize(buff)
144144

145145
self.execute_type = SEND_FEEDBACK
@@ -155,7 +155,7 @@ def on_succeed(self, event):
155155

156156
try:
157157
self.result_msg = yaml_msg_str(self.action_type.result, self.result.GetValue())
158-
buff = StringIO()
158+
buff = BytesIO()
159159
self.result_msg.serialize(buff)
160160

161161
self.execute_type = SUCCEED

actionlib_tools/setup.py

+11
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
#!/usr/bin/env python3
2+
3+
from setuptools import setup
4+
from catkin_pkg.python_setup import generate_distutils_setup
5+
6+
d = generate_distutils_setup(
7+
packages=['actionlib_tools'],
8+
package_dir={'': 'src'}
9+
)
10+
11+
setup(**d)

actionlib_tools/src/actionlib_tools/__init__.py

Whitespace-only changes.

actionlib_tools/scripts/dynamic_action.py actionlib_tools/src/actionlib_tools/dynamic_action.py

-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,3 @@
1-
#! /usr/bin/python
21
# **********************************************************
32
# Software License Agreement (BSD License)
43
#

0 commit comments

Comments
 (0)