test_footsteps.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import roslib
4 roslib.load_manifest('naoqi_driver')
5 import rospy
6 from rospy.exceptions import ROSException
7 
8 
9 import roslib.rostime
10 from roslib.rostime import Duration
11 
12 
13 import std_srvs
14 from std_srvs.srv import Empty
15 import humanoid_nav_msgs
16 from humanoid_nav_msgs.msg import StepTarget
17 from humanoid_nav_msgs.srv import StepTargetService, StepTargetServiceRequest
18 
20  inhibitWalkSrv = rospy.ServiceProxy("inhibit_walk", std_srvs.srv.Empty)
21  uninhibitWalkSrv = rospy.ServiceProxy("uninhibit_walk", std_srvs.srv.Empty)
22 
23 
24 
25  rospy.loginfo("Waiting for footstep server...")
26  rospy.wait_for_service('footstep_srv')
27  client = rospy.ServiceProxy("footstep_srv", humanoid_nav_msgs.srv.StepTargetService)
28  rospy.loginfo("Done.")
29 
30 # try:
31  goal = StepTarget()
32  goal.leg = 0
33  goal.pose.x = 0.08
34  goal.pose.theta = 0.3
35  client(goal)
36 
37  goal.leg = 1
38  goal.pose.theta = 0.3
39  client(goal)
40 
41  goal.leg = 0
42  goal.pose.x = 0.0
43  goal.pose.y = -0.16
44  client(goal)
45 
46  goal.leg = 1
47  goal.pose.x = 0.00
48  goal.pose.y = 0.088
49  goal.pose.theta = 0.0
50  client(goal)
51 
52  goal.leg = 0
53  goal.pose.x = 0.0
54  goal.pose.y = -0.16
55  client(goal)
56 
57  goal.leg = 1
58  goal.pose.x = 0.00
59  goal.pose.y = 0.0
60  goal.pose.theta = 0.0
61  client(goal)
62 
63 
64 
65 if __name__ == '__main__':
66  try:
67  rospy.init_node('footstep_test_client')
69 
70  except rospy.ROSInterruptException:
71  print "program interrupted before completion"
72 


nao_apps
Author(s):
autogenerated on Mon Jun 10 2019 14:04:55