2 import roslib; roslib.load_manifest(
'openni_camera')
5 from sensor_msgs.msg
import Image
17 rospy.init_node(
'test_sub', log_level=rospy.DEBUG)
22 consecutive_failures = 0
23 while not rospy.is_shutdown()
and consecutive_failures < 5:
27 topic =
"image_%d" % attempt
29 sub = rospy.Subscriber(topic, Image, callback, callback_args=received)
31 command =
"rosrun openni_camera openni_node_unstable depth/image_raw:=%s" % topic
32 tmp = tempfile.TemporaryFile(mode=
'r+')
34 p = subprocess.Popen(shlex.split(command), stdout=tmp, stderr=subprocess.STDOUT)
37 while (
not rospy.is_shutdown())
and (time.time() < end)
and (
not received[0]):
39 duration = time.time() - start
42 p.send_signal(signal.SIGINT)
43 end = time.time() + 5.0
45 while p.returncode
is None and time.time() < end:
48 if p.returncode
is None:
49 print(
"Escalating to SIGTERM!")
51 end = time.time() + 5.0
53 while p.returncode
is None and time.time() < end:
56 if p.returncode
is None:
57 print(
"Escalating to SIGKILL!!")
61 if not rospy.is_shutdown():
63 rospy.loginfo(
"Succeeded in %.1fs", duration)
64 successes = successes + 1
65 consecutive_failures = 0
68 rospy.logerr(
"Failed!")
69 failures = failures + 1
70 consecutive_failures = consecutive_failures + 1
73 with open(
"%s_%05d.log" % (status, attempt),
'w')
as f:
75 shutil.copyfileobj(tmp, f)
78 core_name =
"core_%d" % attempt
79 os.rename(
"core", core_name)
80 print(
"Core dump %s" % core_name)
84 print(
"Successes: %d" % successes)
85 print(
"Failures: %d" % failures)