plan_footsteps.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 #
4 # A simple service client calling a running footstep_planner node.
5 # Using this program you can request footstep plans from the command line.
6 #
7 # Author: Armin Hornung, University of Freiburg
8 #
9 # This is program is part of the ROS footstep planner:
10 # http://www.ros.org/wiki/footstep_planner
11 # License: GPL 3
12 #
13 
14 import roslib
15 from humanoid_nav_msgs.msg._StepTarget import StepTarget
16 roslib.load_manifest('footstep_planner')
17 import rospy
18 
19 from humanoid_nav_msgs.srv import *
20 from geometry_msgs.msg import Pose2D
21 
22 import sys
23 
24 
25 if __name__ == '__main__':
26  if len(sys.argv) != 7 and len(sys.argv) != 13:
27  sys.exit('\nUSAGE: %s <start> <goal>\n where <start> and <goal> consist of "x y theta" in world coordinates\n\n' % sys.argv[0])
28 
29  rospy.init_node('plan_footsteps')
30 
31  if len(sys.argv) ==7:
32  planSrv = rospy.ServiceProxy("plan_footsteps", PlanFootsteps)
33  start = Pose2D()
34  goal = Pose2D()
35 
36  start.x = float(sys.argv[1])
37  start.y = float(sys.argv[2])
38  start.theta = float(sys.argv[3])
39 
40  goal.x = float(sys.argv[4])
41  goal.y = float(sys.argv[5])
42  goal.theta = float(sys.argv[6])
43 
44  rospy.loginfo("Calling footstep planner service from (%f %f %f) to (%f %f %f)...",
45  start.x, start.y, start.theta, goal.x, goal.y, goal.theta)
46  resp = planSrv(start, goal)
47  else:
48  planSrv = rospy.ServiceProxy("plan_footsteps_feet", PlanFootstepsBetweenFeet)
49  start_left = StepTarget()
50  start_right = StepTarget()
51  goal_left = StepTarget()
52  goal_right = StepTarget()
53 
54  start_left.pose.x = float(sys.argv[1])
55  start_left.pose.y = float(sys.argv[2])
56  start_left.pose.theta = float(sys.argv[3])
57  start_right.pose.x = float(sys.argv[4])
58  start_right.pose.y = float(sys.argv[5])
59  start_right.pose.theta = float(sys.argv[6])
60 
61  goal_left.pose.x = float(sys.argv[7])
62  goal_left.pose.y = float(sys.argv[8])
63  goal_left.pose.theta = float(sys.argv[9])
64  goal_right.pose.x = float(sys.argv[10])
65  goal_right.pose.y = float(sys.argv[11])
66  goal_right.pose.theta = float(sys.argv[12])
67 
68  resp = planSrv(start_left, start_right, goal_left, goal_right);
69 
70  if resp.result == True:
71  rospy.loginfo("Planning succeeded with %d steps, path costs: %f" % (len(resp.footsteps), resp.costs))
72  print "Footsteps:"
73  for f in resp.footsteps:
74  print ("L" if (f.leg == StepTarget.left) else "R") + " [%f %f %f]" % (f.pose.x, f.pose.y, f.pose.theta)
75  else:
76  rospy.logerr("Service call failed")
77 
78  exit(0)


footstep_planner
Author(s): Johannes Garimort, Armin Hornung
autogenerated on Mon Jun 10 2019 13:38:24