41 NAME =
'test_base_vw_gt'
45 roslib.load_manifest(PKG)
50 from geometry_msgs.msg
import Twist,Vector3
60 from test_base
import BaseTest, Q, E
76 error = abs(p3d.twist.twist.angular.z - TARGET_VW)
77 print(
" Error: " + str(error) +
" Duration: " + str(time.time() - self.
duration_start))
80 if error < TARGET_TOL:
88 if error < TARGET_TOL:
94 timeout_t = time.time() + TEST_DURATION
95 while not rospy.is_shutdown()
and not self.
success and time.time() < timeout_t:
96 self.
pub.publish(Twist(Vector3(0.0,0.0,0), Vector3(0,0,TARGET_VW)))
100 if __name__ ==
'__main__':
101 rostest.run(PKG, sys.argv[0], VW_GT, sys.argv)