15 from humanoid_nav_msgs.msg._StepTarget
import StepTarget
16 roslib.load_manifest(
'footstep_planner')
20 from geometry_msgs.msg
import Pose2D
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])
29 rospy.init_node(
'plan_footsteps')
32 planSrv = rospy.ServiceProxy(
"plan_footsteps", PlanFootsteps)
36 start.x = float(sys.argv[1])
37 start.y = float(sys.argv[2])
38 start.theta = float(sys.argv[3])
40 goal.x = float(sys.argv[4])
41 goal.y = float(sys.argv[5])
42 goal.theta = float(sys.argv[6])
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)
48 planSrv = rospy.ServiceProxy(
"plan_footsteps_feet", PlanFootstepsBetweenFeet)
49 start_left = StepTarget()
50 start_right = StepTarget()
51 goal_left = StepTarget()
52 goal_right = StepTarget()
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])
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])
68 resp =
planSrv(start_left, start_right, goal_left, goal_right);
70 if resp.result ==
True:
71 rospy.loginfo(
"Planning succeeded with %d steps, path costs: %f" % (len(resp.footsteps), resp.costs))
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)
76 rospy.logerr(
"Service call failed")