diff --git a/get_obj_dist/src/human_2d_to_3d.py b/get_obj_dist/src/human_2d_to_3d.py
index 9830da8576eabe2aa1c8d472d8eea69cb28ab3b9..43fcfd07237ce882e502aed0b8303012885f2e75 100755
--- a/get_obj_dist/src/human_2d_to_3d.py
+++ b/get_obj_dist/src/human_2d_to_3d.py
@@ -243,5 +243,5 @@ def main(args):
 
 
 if __name__ == '__main__':
-    rospy.set_param("use_sim_time", 'true')
+    #rospy.set_param("use_sim_time", 'true')
     main(sys.argv)
diff --git a/human_detection/src/human_detector.py b/human_detection/src/human_detector.py
index 08b108416f1b0b5a2bd562c0333a966ac80f23f7..20ded33b0591e73437d0ab436f8124c4b91212df 100755
--- a/human_detection/src/human_detector.py
+++ b/human_detection/src/human_detector.py
@@ -76,7 +76,7 @@ class human_detector:
         rospy.loginfo(rospy.get_name() + ": " + text)
 
         self.bridge = CvBridge()
-        self.image_sub = rospy.Subscriber("~camera/color/image_raw", Image, self.callback)
+        self.image_sub = rospy.Subscriber("~camera/color/image_raw", Image, self.callback, queue_size=1, buff_size=6291456)
 
         self.image_pub = rospy.Publisher("~detection_image", Image, queue_size=1)
         self.bbx_pub = rospy.Publisher("~bounding_box", box_list, queue_size=1)
@@ -119,26 +119,6 @@ class human_detector:
             line_thickness=8,
             min_score_thresh=0.60)
 
-        # Calculate frame time
-        t1 = time.time()
-        run_time = t1 - t0
-        if run_time < 1:
-            run_time_list.append(run_time)
-            if len(run_time_list) > 10:
-                del run_time_list[0]
-
-        if len(run_time_list):
-            avg_run_time = round(sum(run_time_list) / len(run_time_list) * 1000, 1)
-            left_margin = 10
-            bottom_margin = 10
-            time_text_position = (left_margin, data.height-bottom_margin)
-            cv2.putText(cv_image, 'Run Time: {}ms'.format(avg_run_time),
-                        time_text_position,
-                        font,
-                        font_scale,
-                        font_color,
-                        line_type)
-
         counter = 0
         list_length = 0
         bbx_list = box_list()
@@ -181,6 +161,30 @@ class human_detector:
 
         self.detection2d_array_pub.publish(det2d_array)
 
+        # Calculate frame time
+        t1 = time.time()
+        run_time = t1 - t0
+        #if run_time < 1:
+        run_time_list.append(run_time)
+        if len(run_time_list) > 10:
+            del run_time_list[0]
+        #else:
+            #print "run_time>1"
+            #rospy.logerr("run_time=%f",run_time)
+
+        if len(run_time_list):
+            avg_run_time = round(sum(run_time_list)*1000 / len(run_time_list) , 1)
+            left_margin = 10
+            bottom_margin = 10
+            time_text_position = (left_margin, data.height-bottom_margin)
+            cv2.putText(cv_image, 'Run Time: {}ms'.format(avg_run_time),
+                        time_text_position,
+                        font,
+                        font_scale,
+                        font_color,
+                        line_type)
+
+
         try:
             cvt_msg = self.bridge.cv2_to_imgmsg(cv_image, "bgr8")
             cvt_msg.header.stamp = data.header.stamp