40 roslib.load_manifest(PKG)
42 import unittest, sys, os, math
58 super(TestSlide, self).
__init__(*args)
68 rospy.loginfo(
"runs hits x y z dx dy dz dr r_tol")
72 dx = p3d.pose.pose.position.x - TARGET_X
73 dy = p3d.pose.pose.position.y - TARGET_Y
74 dz = p3d.pose.pose.position.z - TARGET_Z
75 d = math.sqrt((dx * dx) + (dy * dy))
77 rospy.loginfo(
"self.runs, self.hits, "\
78 "p3d.pose.pose.position.x , p3d.pose.pose.position.y , p3d.pose.pose.position.z, "\
79 "dx , dy , dz , d, TARGET_RAD")
81 if (d < TARGET_RAD
and abs(dz) < CUP_HEIGHT):
83 if (self.
runs > 10
and self.
runs < 50):
84 rospy.logwarn(
"Got to goal too quickly! (",self.
runs,
")")
88 if (self.
hits > MIN_HITS):
89 if (self.
runs > MIN_RUNS):
96 rospy.Subscriber(
"/base_pose_ground_truth", Odometry, self.
positionInput)
97 rospy.init_node(NAME, anonymous=
True)
98 timeout_t = time.time() + TEST_DURATION
99 while not rospy.is_shutdown()
and not self.
success and not self.
fail and time.time() < timeout_t:
107 if __name__ ==
'__main__':
108 rostest.run(PKG, sys.argv[0], TestSlide, sys.argv)
def positionInput(self, p3d)