1- #!/usr/bin/env python3
1+ #!/usr/bin/env python
22
33# -- BEGIN LICENSE BLOCK ----------------------------------------------
44# Copyright 2021 FZI Forschungszentrum Informatik
2525#
2626#
2727# ---------------------------------------------------------------------
28-
2928import sys
3029
3130import rospy
@@ -41,6 +40,10 @@ from cartesian_control_msgs.msg import (
4140 CartesianTrajectoryPoint ,
4241)
4342
43+ # Compatibility for python2 and python3
44+ if sys .version_info [0 ] < 3 :
45+ input = raw_input
46+
4447# If your robot description is created with a tf_prefix, those would have to be adapted
4548JOINT_NAMES = [
4649 "shoulder_pan_joint" ,
@@ -199,7 +202,7 @@ class TrajectoryClient:
199202 )
200203 valid = input_str in ["y" , "n" ]
201204 if not valid :
202- print ("Please confirm by entering 'y' or abort by entering 'n'" )
205+ rospy . loginfo ("Please confirm by entering 'y' or abort by entering 'n'" )
203206 else :
204207 confirmed = input_str == "y"
205208 if not confirmed :
@@ -208,11 +211,11 @@ class TrajectoryClient:
208211
209212 def choose_controller (self ):
210213 """Ask the user to select the desired controller from the available list."""
211- print ("Available trajectory controllers:" )
214+ rospy . loginfo ("Available trajectory controllers:" )
212215 for (index , name ) in enumerate (JOINT_TRAJECTORY_CONTROLLERS ):
213- print ("{} (joint-based): {}" .format (index , name ))
216+ rospy . loginfo ("{} (joint-based): {}" .format (index , name ))
214217 for (index , name ) in enumerate (CARTESIAN_TRAJECTORY_CONTROLLERS ):
215- print ("{} (Cartesian): {}" .format (index + len (JOINT_TRAJECTORY_CONTROLLERS ), name ))
218+ rospy . loginfo ("{} (Cartesian): {}" .format (index + len (JOINT_TRAJECTORY_CONTROLLERS ), name ))
216219 choice = - 1
217220 while choice < 0 :
218221 input_str = input (
@@ -224,13 +227,13 @@ class TrajectoryClient:
224227 if choice < 0 or choice >= len (JOINT_TRAJECTORY_CONTROLLERS ) + len (
225228 CARTESIAN_TRAJECTORY_CONTROLLERS
226229 ):
227- print (
230+ rospy . loginfo (
228231 "{} not inside the list of options. "
229232 "Please enter a valid index from the list above." .format (choice )
230233 )
231234 choice = - 1
232235 except ValueError :
233- print ("Input is not a valid number. Please try again." )
236+ rospy . loginfo ("Input is not a valid number. Please try again." )
234237 if choice < len (JOINT_TRAJECTORY_CONTROLLERS ):
235238 self .joint_trajectory_controller = JOINT_TRAJECTORY_CONTROLLERS [choice ]
236239 return "joint_based"
0 commit comments