def test_random_record(self):
    rospy.init_node('random_pub')
  
    if (len(sys.argv) < 2):
      raise Exception("Expected seed as first argument")

    seed = int(sys.argv[1])

    seed    = int(sys.argv[1])
    topics  = int(sys.argv[2])
    length  = float(sys.argv[3])

    rmg = RandomMsgGen(seed, topics, length)

    publishers = {}

    for (topic, msg_class) in rmg.topics():
      publishers[topic] = rospy.Publisher(topic, msg_class)

    bagpath = os.path.join('/tmp', 'test_rosbag_random_record_%d'%seed)
    cmd = ['rosbag', 'record', '-a', '-O', bagpath]
    f1 = subprocess.Popen(cmd)

    def finalkill():
      try:
        os.kill(f1.pid, signal.SIGKILL)
      except:
        pass

    atexit.register(finalkill)

    # Sleep an extra 5 seconds for good measure
    rospy.sleep(rospy.Duration.from_sec(5.0))

    start = rospy.Time.now()
    for (topic, msg, time) in rmg.messages():
      d = start + rospy.Duration.from_sec(time) - rospy.Time.now()
      rospy.sleep(d)
      publishers[topic].publish(msg)

    # Sleep an extra 5 seconds for good measure
    rospy.sleep(rospy.Duration.from_sec(5.0))

    # Initial terminate using SIGINT so bag clean up nicely
    os.kill(f1.pid, signal.SIGINT)

    # Sleep an extra 5 seconds for good measure
    rospy.sleep(rospy.Duration.from_sec(5.0))

    # Keep trying to kill until it's dead instead of blocking on communicate
    while (f1.poll() is None):
      try:
        os.kill(f1.pid, signal.SIGKILL)
      except:
        pass
      rospy.sleep(rospy.Duration.from_sec(1.0))
      
    self.assertEqual(f1.returncode, 0)
    def test_random_play(self):
        rospy.init_node('random_sub', anonymous=True)

        self.start = None
        self.input = []

        self.assertTrue(len(sys.argv[1]) > 3)

        seed = int(sys.argv[1])
        topics = int(sys.argv[2])
        length = float(sys.argv[3])
        scale = float(sys.argv[4])
        self.use_clock = bool(int(sys.argv[5]))

        rmg = RandomMsgGen(int(seed), topics, length)

        subscribers = {}
        for (topic, msg_class) in rmg.topics():
            subscribers[topic] = rospy.Subscriber(topic, msg_class,
                                                  self.msg_cb_topic(topic))

        bagpath = os.path.join('/tmp',
                               'test_rosbag_random_record_%d.bag' % seed)
        cmd = ['rosbag', 'play', '-d', str(DELAY), '-r', str(scale)]

        rospy.loginfo(str(cmd))

        if (self.use_clock):
            cmd += ['--clock', '--hz', '100']

        cmd += [bagpath]

        try:
            f1 = subprocess.Popen(cmd)

            last_input_count = 0
            while (len(self.input) < rmg.message_count()):
                #        print "\n%d/%d\n"%(len(self.input), rmg.message_count())
                time.sleep(1.0)
                # abort loop if no input is coming in anymore and process has finished
                if len(self.input) == last_input_count:
                    rc = f1.poll()
                    if rc is not None:
                        self.assertEqual(rc, 0)
                        break
                last_input_count = len(self.input)

            self.assertEqual(len(self.input), rmg.message_count())

            max_late = 0
            max_early = 0
            avg_off = 0
            power = 0

            for (expect_topic, expect_msg, expect_time) in rmg.messages():

                if (not self.use_clock):
                    expect_time /= scale

                buff = StringIO()
                expect_msg.serialize(buff)
                expect_msg.deserialize(buff.getvalue())

                msg_match = False

                for ind in range(0, 100):
                    (input_topic, input_msg, input_time) = self.input[ind]

                    if (genpy.message.strify_message(expect_msg) ==
                            genpy.message.strify_message(input_msg)):
                        msg_match = True
                        del self.input[ind]

                        # stats
                        diff = input_time - expect_time

                        if (diff < max_early):
                            max_early = diff

                        if (diff > max_late):
                            max_late = diff

                        avg_off += diff / rmg.message_count()

                        power += (diff**2) / rmg.message_count()

                        # Messages can arrive late, but never very early Both of
                        # these bounds are much larger than they ought to be, but
                        # you never know with a heavily loaded system.
                        self.assertTrue(input_time - expect_time > -.5)
                        self.assertTrue(abs(input_time - expect_time) < .5)
                        break

                if not msg_match:
                    print("No match at time: %f" % expect_time)

                self.assertTrue(msg_match)

            print("%f %f %f %f" % (max_early, max_late, avg_off, power))

        finally:
            f1.communicate()

        self.assertEqual(f1.returncode, 0)
Exemple #3
0
  def test_random_play(self):
    rospy.init_node('random_sub', anonymous=True)

    self.start = None
    self.input = []

    self.assertTrue(len(sys.argv[1]) > 3)

    seed    = int(sys.argv[1])
    topics  = int(sys.argv[2])
    length  = float(sys.argv[3])
    scale   = float(sys.argv[4])
    self.use_clock = bool(int(sys.argv[5]))

    rmg = RandomMsgGen(int(seed), topics, length)

    subscribers = {}
    for (topic, msg_class) in rmg.topics():
      subscribers[topic] = rospy.Subscriber(topic, msg_class, self.msg_cb_topic(topic))

    bagpath = os.path.join('/tmp', 'test_rosbag_random_record_%d.bag'%seed)
    cmd = ['rosbag', 'play', '-d', str(DELAY), '-r', str(scale)]
    
    rospy.loginfo(str(cmd))

    if (self.use_clock):
      cmd += ['--clock', '--hz', '100']

    cmd += [bagpath]

    try:
      f1 = subprocess.Popen(cmd)

      last_input_count = 0
      while (len(self.input) < rmg.message_count()):
#        print "\n%d/%d\n"%(len(self.input), rmg.message_count())
        time.sleep(1.0)
        # abort loop if no input is coming in anymore and process has finished
        if len(self.input) == last_input_count:
          rc = f1.poll()
          if rc is not None:
            self.assertEqual(rc, 0)
            break
        last_input_count = len(self.input)

      self.assertEqual(len(self.input), rmg.message_count())

      max_late = 0
      max_early = 0
      avg_off = 0
      power = 0

      for (expect_topic, expect_msg, expect_time) in rmg.messages():

        if (not self.use_clock):
          expect_time /= scale

        buff = StringIO()
        expect_msg.serialize(buff)
        expect_msg.deserialize(buff.getvalue())

        msg_match = False

        for ind in range(0,100):
          (input_topic, input_msg, input_time) = self.input[ind]

          if (genpy.message.strify_message(expect_msg) == genpy.message.strify_message(input_msg)):
            msg_match = True
            del self.input[ind]

            # stats
            diff = input_time - expect_time

            if (diff < max_early):
              max_early = diff

            if (diff > max_late):
              max_late = diff

            avg_off += diff / rmg.message_count()

            power += (diff**2) / rmg.message_count()

            # Messages can arrive late, but never very early Both of
            # these bounds are much larger than they ought to be, but
            # you never know with a heavily loaded system.
            self.assertTrue(input_time - expect_time > -.5)
            self.assertTrue(abs(input_time - expect_time) < .5)
            break

        if not msg_match:
          print("No match at time: %f" % expect_time)

        self.assertTrue(msg_match)

      print("%f %f %f %f"%(max_early, max_late, avg_off, power))

    finally:
      f1.communicate()

    self.assertEqual(f1.returncode, 0)
Exemple #4
0
import roslib
roslib.load_manifest('test_rosrecord')

import rospy
import sys
import time

from random_messages import RandomMsgGen

if __name__ == '__main__':
    rospy.init_node('random_pub')

    if (len(sys.argv) < 2):
        raise Exception("Expected seed as first argument")

    rmg = RandomMsgGen(int(sys.argv[1]), 10, 10.0)

    publishers = {}

    for (topic, msg_class) in rmg.topics():
        publishers[topic] = rospy.Publisher(topic, msg_class)

    r = rospy.Rate(10)
    while (not rospy.has_param('/spew')):
        r.sleep()

    # Sleep an extra 5 seconds for good measure
    rospy.sleep(rospy.Duration.from_sec(5.0))

    start = rospy.Time.now()
    for (topic, msg, time) in rmg.messages():