Skip to content

Commit

Permalink
towards python3 support (moveit#1054)
Browse files Browse the repository at this point in the history
* detect correct version of python/boost-python

There is no need to hardcode python2 in here anymore.
Instead rely on whatever ROS was configured to use.

https://www.boost.org/doc/libs/1_68_0/libs/python/doc/html/rn.html#rn.version_1_67
Additionally current releases of boost use python27/python36 for the component.

* moveitjoy: fix single print statement

* moveit_commander: fix print function usage

* moveit_commander: fix many implicit local includes

Python3 requires these to be explicit.

* moveit_commander: python3-compatible cli input
  • Loading branch information
v4hn authored and mlautman committed Sep 19, 2018
1 parent ec287f0 commit 8c62cf2
Show file tree
Hide file tree
Showing 6 changed files with 50 additions and 31 deletions.
31 changes: 19 additions & 12 deletions moveit_commander/bin/moveit_commander_cmdline.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
#!/usr/bin/env python

from __future__ import print_function

import roslib
import rospy
import readline
Expand All @@ -10,6 +12,11 @@
import argparse
from moveit_commander import MoveGroupCommandInterpreter, MoveGroupInfoLevel, roscpp_initialize, roscpp_shutdown

# compatibility with python3
# python2's input function is dangerous anyway
if hasattr(__builtin__, 'raw_input'):
input = raw_input

class bcolors:
HEADER = '\033[95m'
OKBLUE = '\033[94m'
Expand Down Expand Up @@ -62,15 +69,15 @@ def complete(self, text, state):

def print_message(level, msg):
if level == MoveGroupInfoLevel.FAIL:
print bcolors.FAIL + msg + bcolors.ENDC
print(bcolors.FAIL + msg + bcolors.ENDC)
elif level == MoveGroupInfoLevel.WARN:
print bcolors.WARNING + msg + bcolors.ENDC
print(bcolors.WARNING + msg + bcolors.ENDC)
elif level == MoveGroupInfoLevel.SUCCESS:
print bcolors.OKGREEN + msg + bcolors.ENDC
print(bcolors.OKGREEN + msg + bcolors.ENDC)
elif level == MoveGroupInfoLevel.DEBUG:
print bcolors.OKBLUE + msg + bcolors.ENDC
print(bcolors.OKBLUE + msg + bcolors.ENDC)
else:
print msg
print(msg)

def get_context_keywords(interpreter):
kw = interpreter.get_keywords()
Expand All @@ -84,9 +91,9 @@ def run_interactive(group_name):
completer = SimpleCompleter(get_context_keywords(c))
readline.set_completer(completer.complete)

print
print bcolors.HEADER + "Waiting for commands. Type 'help' to get a list of known commands." + bcolors.ENDC
print
print()
print(bcolors.HEADER + "Waiting for commands. Type 'help' to get a list of known commands." + bcolors.ENDC)
print()
readline.parse_and_bind('tab: complete')

while not rospy.is_shutdown():
Expand All @@ -96,7 +103,7 @@ def run_interactive(group_name):
ag = c.get_active_group()
if ag != None:
name = ag.get_name()
cmd = raw_input(bcolors.OKBLUE + name + '> ' + bcolors.ENDC)
cmd = input(bcolors.OKBLUE + name + '> ' + bcolors.ENDC)
except:
break
cmdorig = cmd.strip()
Expand All @@ -120,7 +127,7 @@ def run_service(group_name):
if len(group_name) > 0:
c.execute("use " + group_name)
# add service stuff
print "Running ROS service"
print("Running ROS service")
rospy.spin()

def stop_ros(reason):
Expand All @@ -129,7 +136,7 @@ def stop_ros(reason):

def sigint_handler(signal, frame):
stop_ros("Ctrl+C pressed")
# this won't actually exit, but trigger an exception to terminate raw_input
# this won't actually exit, but trigger an exception to terminate input
sys.exit(0)

if __name__=='__main__':
Expand Down Expand Up @@ -157,4 +164,4 @@ def sigint_handler(signal, frame):

stop_ros("Done")

print "Bye bye!"
print("Bye bye!")
12 changes: 6 additions & 6 deletions moveit_commander/src/moveit_commander/__init__.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
from exception import *
from roscpp_initializer import *
from planning_scene_interface import *
from move_group import *
from robot import *
from interpreter import *
from .exception import *
from .roscpp_initializer import *
from .planning_scene_interface import *
from .move_group import *
from .robot import *
from .interpreter import *
4 changes: 2 additions & 2 deletions moveit_commander/src/moveit_commander/move_group.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,8 @@
import rospy
import tf
from moveit_ros_planning_interface import _moveit_move_group_interface
from exception import MoveItCommanderException
import conversions
from .exception import MoveItCommanderException
import moveit_commander.conversions as conversions

class MoveGroupCommander(object):
"""
Expand Down
2 changes: 1 addition & 1 deletion moveit_commander/src/moveit_commander/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
from moveit_ros_planning_interface import _moveit_robot_interface
from moveit_msgs.msg import RobotState
from visualization_msgs.msg import MarkerArray
import conversions
import moveit_commander.conversions as conversions


class RobotCommander(object):
Expand Down
28 changes: 19 additions & 9 deletions moveit_ros/planning_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,15 +7,6 @@ if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE)
set(CMAKE_BUILD_TYPE Release)
endif()

find_package(Boost REQUIRED COMPONENTS
date_time
filesystem
program_options
python
system
thread
)
find_package(PythonLibs 2.7 REQUIRED)
find_package(catkin REQUIRED COMPONENTS
moveit_msgs
moveit_ros_planning
Expand All @@ -30,6 +21,25 @@ find_package(catkin REQUIRED COMPONENTS
rospy
rosconsole
)

find_package(PythonInterp REQUIRED)
find_package(PythonLibs "${PYTHON_VERSION_MAJOR}.${PYTHON_VERSION_MINOR}" REQUIRED)

find_package(Boost REQUIRED)
if(Boost_VERSION LESS 106700)
set(BOOST_PYTHON_COMPONENT python)
elseif()
set(BOOST_PYTHON_COMPONENT python${PYTHON_VERSION_MAJOR}${PYTHON_VERSION_MINOR})
endif()

find_package(Boost REQUIRED COMPONENTS
date_time
filesystem
program_options
${BOOST_PYTHON_COMPONENT}
system
thread
)
find_package(Eigen3 REQUIRED)

# Eigen 3.2 (Wily) only provides EIGEN3_INCLUDE_DIR, not EIGEN3_INCLUDE_DIRS
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,8 @@
# Author: Ryohei Ueda, Dave Coleman
# Desc: Interface between PS3/XBox controller and MoveIt! Motion Planning Rviz Plugin

from __future__ import print_function

import xml.dom.minidom
from operator import add
import sys
Expand Down Expand Up @@ -358,7 +360,7 @@ def parseSRDF(self):
if len(planning_groups[name]) == 0:
del planning_groups[name]
else:
print name, planning_groups[name]
print(name, planning_groups[name])
self.planning_groups = planning_groups
self.planning_groups_keys = planning_groups.keys() #we'd like to store the 'order'
self.frame_id = ri.get_planning_frame()
Expand Down

0 comments on commit 8c62cf2

Please sign in to comment.