Skip to content

Commit 04cd003

Browse files
authored
Python3 migration (moveit#536)
* Python3 migration of move_group_python_interface_tutorial * Python3 migration of collision_enviroments
1 parent f0ac33f commit 04cd003

File tree

5 files changed

+44
-42
lines changed

5 files changed

+44
-42
lines changed

CMakeLists.txt

+2-1
Original file line numberDiff line numberDiff line change
@@ -67,4 +67,5 @@ add_subdirectory(doc/tests)
6767
add_subdirectory(doc/controller_configuration)
6868
add_subdirectory(doc/trajopt_planner)
6969
add_subdirectory(doc/creating_moveit_plugins/lerp_motion_planner)
70-
add_subdirectory(doc/moveit_cpp)
70+
add_subdirectory(doc/moveit_cpp)
71+
add_subdirectory(doc/collision_environments)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
catkin_install_python(PROGRAMS
2+
scripts/collision_scene_example.py
3+
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
4+
)

doc/collision_environments/scripts/collision_scene_example.py

+9-5
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,8 @@
11
#!/usr/bin/env python
2+
3+
# Python 2/3 compatibility import
4+
from __future__ import print_function
5+
26
import rospy
37
from moveit_commander import RobotCommander, PlanningSceneInterface
48
import geometry_msgs.msg
@@ -16,7 +20,7 @@ def __init__(self):
1620
self.robot = RobotCommander()
1721

1822
# pause to wait for rviz to load
19-
print "============ Waiting while RVIZ displays the scene with obstacles..."
23+
print("============ Waiting while RVIZ displays the scene with obstacles...")
2024

2125
# TODO: need to replace this sleep by explicitly waiting for the scene to be updated.
2226
rospy.sleep(2)
@@ -27,7 +31,7 @@ def add_one_box(self):
2731

2832
self.add_box_object("box1", box1_dimensions, box1_pose)
2933

30-
print "============ Added one obstacle to RViz!!"
34+
print("============ Added one obstacle to RViz!!")
3135

3236
def add_four_boxes(self):
3337
box1_pose = [0.20, 0.50, 0.25, 0, 0, 0, 1]
@@ -47,7 +51,7 @@ def add_four_boxes(self):
4751
self.add_box_object("box3", box3_dimensions, box3_pose)
4852
self.add_box_object("box4", box4_dimensions, box4_pose)
4953

50-
print "========== Added 4 obstacles to the scene!!"
54+
print("========== Added 4 obstacles to the scene!!")
5155

5256
def add_box_object(self, name, dimensions, pose):
5357
p = geometry_msgs.msg.PoseStamped()
@@ -70,12 +74,12 @@ def add_box_object(self, name, dimensions, pose):
7074
load_scene = CollisionSceneExample()
7175

7276
if (len(sys.argv) != 2):
73-
print "Correct usage:: \n\"rosrun moveit_tutorials collision_scene_example.py cluttered\" OR \n\"rosrun moveit_tutorials collision_scene_example.py sparse\""
77+
print("Correct usage:: \n\"rosrun moveit_tutorials collision_scene_example.py cluttered\" OR \n\"rosrun moveit_tutorials collision_scene_example.py sparse\"")
7478
sys.exit()
7579
if sys.argv[1] == "cluttered":
7680
load_scene.add_four_boxes();
7781
elif sys.argv[1] == "sparse":
7882
load_scene.add_one_box();
7983
else:
80-
print "Please specify correct type of scene as cluttered or sparse"
84+
print("Please specify correct type of scene as cluttered or sparse")
8185
sys.exit()

doc/move_group_python_interface/CMakeLists.txt

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
install(PROGRAMS
1+
catkin_install_python(PROGRAMS
22
scripts/move_group_python_interface_tutorial.py
33
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
44
)

doc/move_group_python_interface/scripts/move_group_python_interface_tutorial.py

+28-35
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,10 @@
4141
## and a `RobotCommander`_ class. More on these below. We also import `rospy`_ and some messages that we will use:
4242
##
4343

44+
# Python 2/3 compatibility imports
45+
from __future__ import print_function
46+
from six.moves import input
47+
4448
import sys
4549
import copy
4650
import rospy
@@ -119,21 +123,21 @@ def __init__(self):
119123
## ^^^^^^^^^^^^^^^^^^^^^^^^^
120124
# We can get the name of the reference frame for this robot:
121125
planning_frame = move_group.get_planning_frame()
122-
print "============ Planning frame: %s" % planning_frame
126+
print("============ Planning frame: %s" % planning_frame)
123127

124128
# We can also print the name of the end-effector link for this group:
125129
eef_link = move_group.get_end_effector_link()
126-
print "============ End effector link: %s" % eef_link
130+
print("============ End effector link: %s" % eef_link)
127131

128132
# We can get a list of all the groups in the robot:
129133
group_names = robot.get_group_names()
130-
print "============ Available Planning Groups:", robot.get_group_names()
134+
print("============ Available Planning Groups:", robot.get_group_names())
131135

132136
# Sometimes for debugging it is useful to print the entire state of the
133137
# robot:
134-
print "============ Printing robot state"
135-
print robot.get_current_state()
136-
print ""
138+
print("============ Printing robot state")
139+
print(robot.get_current_state())
140+
print("")
137141
## END_SUB_TUTORIAL
138142

139143
# Misc variables
@@ -449,58 +453,47 @@ def remove_box(self, timeout=4):
449453

450454
def main():
451455
try:
452-
print ""
453-
print "----------------------------------------------------------"
454-
print "Welcome to the MoveIt MoveGroup Python Interface Tutorial"
455-
print "----------------------------------------------------------"
456-
print "Press Ctrl-D to exit at any time"
457-
print ""
458-
print "============ Press `Enter` to begin the tutorial by setting up the moveit_commander ..."
459-
raw_input()
456+
print("")
457+
print("----------------------------------------------------------")
458+
print("Welcome to the MoveIt MoveGroup Python Interface Tutorial")
459+
print("----------------------------------------------------------")
460+
print("Press Ctrl-D to exit at any time")
461+
print("")
462+
input("============ Press `Enter` to begin the tutorial by setting up the moveit_commander ...")
460463
tutorial = MoveGroupPythonIntefaceTutorial()
461464

462-
print "============ Press `Enter` to execute a movement using a joint state goal ..."
463-
raw_input()
465+
input("============ Press `Enter` to execute a movement using a joint state goal ...")
464466
tutorial.go_to_joint_state()
465467

466-
print "============ Press `Enter` to execute a movement using a pose goal ..."
467-
raw_input()
468+
input("============ Press `Enter` to execute a movement using a pose goal ...")
468469
tutorial.go_to_pose_goal()
469470

470-
print "============ Press `Enter` to plan and display a Cartesian path ..."
471-
raw_input()
471+
input("============ Press `Enter` to plan and display a Cartesian path ...")
472472
cartesian_plan, fraction = tutorial.plan_cartesian_path()
473473

474-
print "============ Press `Enter` to display a saved trajectory (this will replay the Cartesian path) ..."
475-
raw_input()
474+
input("============ Press `Enter` to display a saved trajectory (this will replay the Cartesian path) ...")
476475
tutorial.display_trajectory(cartesian_plan)
477476

478-
print "============ Press `Enter` to execute a saved path ..."
479-
raw_input()
477+
input("============ Press `Enter` to execute a saved path ...")
480478
tutorial.execute_plan(cartesian_plan)
481479

482-
print "============ Press `Enter` to add a box to the planning scene ..."
483-
raw_input()
480+
input("============ Press `Enter` to add a box to the planning scene ...")
484481
tutorial.add_box()
485482

486-
print "============ Press `Enter` to attach a Box to the Panda robot ..."
487-
raw_input()
483+
input("============ Press `Enter` to attach a Box to the Panda robot ...")
488484
tutorial.attach_box()
489485

490-
print "============ Press `Enter` to plan and execute a path with an attached collision object ..."
491-
raw_input()
486+
input("============ Press `Enter` to plan and execute a path with an attached collision object ...")
492487
cartesian_plan, fraction = tutorial.plan_cartesian_path(scale=-1)
493488
tutorial.execute_plan(cartesian_plan)
494489

495-
print "============ Press `Enter` to detach the box from the Panda robot ..."
496-
raw_input()
490+
input("============ Press `Enter` to detach the box from the Panda robot ...")
497491
tutorial.detach_box()
498492

499-
print "============ Press `Enter` to remove the box from the planning scene ..."
500-
raw_input()
493+
input("============ Press `Enter` to remove the box from the planning scene ...")
501494
tutorial.remove_box()
502495

503-
print "============ Python tutorial demo complete!"
496+
print("============ Python tutorial demo complete!")
504497
except rospy.ROSInterruptException:
505498
return
506499
except KeyboardInterrupt:

0 commit comments

Comments
 (0)