39 import roslib; roslib.load_manifest(
'velma_task_cs_ros_interface')
44 from velma_common
import *
45 from rcprg_ros_utils
import exitError
47 from simulation_control_msgs.srv
import EnableSim, EnableSimRequest
49 if __name__ ==
"__main__":
50 rospy.init_node(
'step_run_simulation', anonymous=
False)
55 rospy.wait_for_service(
'/gazebo/enable_sim', timeout=10.0)
56 except rospy.ServiceException, e:
57 print "wait_for_service failed: %s"%e
60 enable_sim = rospy.ServiceProxy(
'/gazebo/enable_sim', EnableSim)
69 while not rospy.is_shutdown():
71 req = EnableSimRequest()
89 print "This test/tutorial executes simple motions"\
92 print "Running python interface for Velma..." 93 velma = VelmaInterface()
94 print "Waiting for VelmaInterface initialization..." 95 if not velma.waitForInit(timeout_s=10.0):
96 print "Could not initialize VelmaInterface\n" 98 print "Initialization ok!\n" 100 diag = velma.getCoreCsDiag()
101 if not diag.motorsReady():
102 print "Motors must be homed and ready to use for this test." 105 print "Motors must be enabled every time after the robot enters safe state." 106 print "If the motors are already enabled, enabling them has no effect." 107 print "Enabling motors..." 108 if velma.enableMotors() != 0:
111 print "Moving to the current position..." 112 js_start = velma.getLastJointState()
113 velma.moveJoint(js_start[1], 0.5, start_time=0.5, position_tol=15.0/180.0*math.pi)
114 error = velma.waitForJoint()
116 print "The action should have ended without error, but the error code is", error
119 print "moving head to position: 0" 121 velma.moveHead(q_dest, 1.0, start_time=0.5)
122 if velma.waitForHead() != 0:
128 print "moving head to position: left" 130 velma.moveHead(q_dest, 3.0, start_time=0.5)
131 if velma.waitForHead() != 0:
137 print "moving head to position: left down" 139 velma.moveHead(q_dest, 2.0, start_time=0.5)
140 if velma.waitForHead() != 0:
146 print "moving head to position: right down" 147 q_dest = (-1.56, 0.7)
148 velma.moveHead(q_dest, 5.0, start_time=0.5)
149 if velma.waitForHead() != 0:
155 print "moving head to position: right" 157 velma.moveHead(q_dest, 2.0, start_time=0.5)
158 if velma.waitForHead() != 0:
164 print "moving head to position: 0" 166 velma.moveHead(q_dest, 3.0, start_time=0.5)
167 if velma.waitForHead() != 0:
def isHeadConfigurationClose(q1, q2, tolerance=0.1)
Check if two configurations of robot neck are close within tolerance.