|
41 | 41 | ## and a `RobotCommander`_ class. More on these below. We also import `rospy`_ and some messages that we will use:
|
42 | 42 | ##
|
43 | 43 |
|
| 44 | +# Python 2/3 compatibility imports |
| 45 | +from __future__ import print_function |
| 46 | +from six.moves import input |
| 47 | + |
44 | 48 | import sys
|
45 | 49 | import copy
|
46 | 50 | import rospy
|
@@ -119,21 +123,21 @@ def __init__(self):
|
119 | 123 | ## ^^^^^^^^^^^^^^^^^^^^^^^^^
|
120 | 124 | # We can get the name of the reference frame for this robot:
|
121 | 125 | planning_frame = move_group.get_planning_frame()
|
122 |
| - print "============ Planning frame: %s" % planning_frame |
| 126 | + print("============ Planning frame: %s" % planning_frame) |
123 | 127 |
|
124 | 128 | # We can also print the name of the end-effector link for this group:
|
125 | 129 | eef_link = move_group.get_end_effector_link()
|
126 |
| - print "============ End effector link: %s" % eef_link |
| 130 | + print("============ End effector link: %s" % eef_link) |
127 | 131 |
|
128 | 132 | # We can get a list of all the groups in the robot:
|
129 | 133 | group_names = robot.get_group_names()
|
130 |
| - print "============ Available Planning Groups:", robot.get_group_names() |
| 134 | + print("============ Available Planning Groups:", robot.get_group_names()) |
131 | 135 |
|
132 | 136 | # Sometimes for debugging it is useful to print the entire state of the
|
133 | 137 | # 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("") |
137 | 141 | ## END_SUB_TUTORIAL
|
138 | 142 |
|
139 | 143 | # Misc variables
|
@@ -449,58 +453,47 @@ def remove_box(self, timeout=4):
|
449 | 453 |
|
450 | 454 | def main():
|
451 | 455 | 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 ...") |
460 | 463 | tutorial = MoveGroupPythonIntefaceTutorial()
|
461 | 464 |
|
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 ...") |
464 | 466 | tutorial.go_to_joint_state()
|
465 | 467 |
|
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 ...") |
468 | 469 | tutorial.go_to_pose_goal()
|
469 | 470 |
|
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 ...") |
472 | 472 | cartesian_plan, fraction = tutorial.plan_cartesian_path()
|
473 | 473 |
|
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) ...") |
476 | 475 | tutorial.display_trajectory(cartesian_plan)
|
477 | 476 |
|
478 |
| - print "============ Press `Enter` to execute a saved path ..." |
479 |
| - raw_input() |
| 477 | + input("============ Press `Enter` to execute a saved path ...") |
480 | 478 | tutorial.execute_plan(cartesian_plan)
|
481 | 479 |
|
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 ...") |
484 | 481 | tutorial.add_box()
|
485 | 482 |
|
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 ...") |
488 | 484 | tutorial.attach_box()
|
489 | 485 |
|
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 ...") |
492 | 487 | cartesian_plan, fraction = tutorial.plan_cartesian_path(scale=-1)
|
493 | 488 | tutorial.execute_plan(cartesian_plan)
|
494 | 489 |
|
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 ...") |
497 | 491 | tutorial.detach_box()
|
498 | 492 |
|
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 ...") |
501 | 494 | tutorial.remove_box()
|
502 | 495 |
|
503 |
| - print "============ Python tutorial demo complete!" |
| 496 | + print("============ Python tutorial demo complete!") |
504 | 497 | except rospy.ROSInterruptException:
|
505 | 498 | return
|
506 | 499 | except KeyboardInterrupt:
|
|
0 commit comments