def __init__(self, topic_prefix, config_file, robot_config_file, write_lock, bag_file): self.topic = topic_prefix + "obstacle_distance" self.test_config = config_file self.robot_config_file = robot_config_file resources_timer_frequency = 100.0 # Hz self.timer_interval = 1 / resources_timer_frequency self.testblock_pipeline = [] self.BfW = BagfileWriter(bag_file, write_lock) # Wait for obstacle_distance node rospy.loginfo(rospy.get_name() + ": Waiting for obstacle distance node...") rospy.wait_for_service( self.robot_config_file["obstacle_distance"]["services"][0]) rospy.loginfo(rospy.get_name() + ": Obstacle distance node found!") self.obstacle_distance_server = rospy.ServiceProxy( self.robot_config_file["obstacle_distance"]["services"][0], GetObstacleDistance) rospy.Timer(rospy.Duration.from_sec(self.timer_interval), self.collect_obstacle_distances)
def __init__(self): self.bag_name = rosparam.get_param("/test_name") self.number_of_tests = rosparam.get_param("/number_of_tests") self.robot_config_file = self.load_data(rosparam.get_param("/robot_config")) if not os.path.exists(rosparam.get_param(rospy.get_name() + "/bagfile_output")): os.makedirs(rosparam.get_param(rospy.get_name() + "/bagfile_output")) self.topic = "/atf/" self.lock_write = Lock() self.bag = rosbag.Bag(rosparam.get_param(rospy.get_name() + "/bagfile_output") + self.bag_name + ".bag", 'w') self.test_config = self.load_data(rosparam.get_param(rospy.get_name() + "/test_config_file") )[rosparam.get_param("/test_config")] recorder_config = self.load_data(rospkg.RosPack().get_path("atf_recorder_plugins") + "/config/recorder_plugins.yaml") self.BfW = BagfileWriter(self.bag, self.lock_write) # Init metric recorder self.recorder_plugin_list = [] for (key, value) in recorder_config.iteritems(): self.recorder_plugin_list.append(getattr(atf_recorder_plugins, value)(self.topic, self.test_config, self.robot_config_file, self.lock_write, self.bag)) self.topic_pipeline = [] self.active_sections = [] self.requested_topics = [] self.testblock_list = self.create_testblock_list() for topic in self.get_topics(): msg_type = rostopic.get_topic_class(topic, blocking=True)[0] rospy.Subscriber(topic, msg_type, self.global_topic_callback, queue_size=5, callback_args=topic) self.test_status_publisher = rospy.Publisher(self.topic + "test_status", TestStatus, queue_size=10) rospy.Service(self.topic + "recorder_command", RecorderCommand, self.command_callback) # Wait for subscriber num_subscriber = self.test_status_publisher.get_num_connections() while num_subscriber == 0: num_subscriber = self.test_status_publisher.get_num_connections() test_status = TestStatus() test_status.test_name = self.bag_name test_status.status_recording = 1 test_status.status_analysing = 0 test_status.total = self.number_of_tests self.test_status_publisher.publish(test_status) rospy.loginfo(rospy.get_name() + ": Node started!")
def __init__(self, topic_prefix, config_file, robot_config_file, write_lock, bag_file): self.topic = topic_prefix + "interface" self.test_config = config_file self.robot_config_file = robot_config_file resources_timer_frequency = 100.0 # Hz self.timer_interval = 1 / resources_timer_frequency self.default_timeout = 20 # s self.testblock_pipeline = [] self.BfW = BagfileWriter(bag_file, write_lock) rospy.Timer(rospy.Duration.from_sec(self.timer_interval), self.check_interfaces)
def __init__(self, topic_prefix, config_file, robot_config_file, write_lock, bag_file): self.topic_prefix = topic_prefix self.test_config = config_file self.resources_timer_frequency = 4.0 # Hz self.timer_interval = 1 / self.resources_timer_frequency self.testblock_list = self.create_testblock_list() self.pid_list = self.create_pid_list() self.requested_nodes = {} self.res_pipeline = {} self.BfW = BagfileWriter(bag_file, write_lock) rospy.Timer(rospy.Duration.from_sec(self.timer_interval), self.collect_resource_data)
def __init__(self, topic_prefix, config_file, robot_config_file, write_lock, bag_file): self.topic_prefix = topic_prefix self.test_config = config_file self.BfW = BagfileWriter(bag_file, write_lock)