diff --git a/.gitignore b/.gitignore index 30bd60effde2c708c3b453273a5e4bb684859502..558af26895021178d5241b674d2e341ff27806aa 100644 --- a/.gitignore +++ b/.gitignore @@ -1,6 +1,7 @@ -.idea +/.vscode *.bag *.pyc +.idea .catkin_workspace -# *CMakeLists.txt \ No newline at end of file +# *CMakeLists.txt diff --git a/get_obj_dist/src/object_to_distance.py b/get_obj_dist/src/object_to_distance.py index b42a91ad460c82836703cd0bd1966525b2c48cac..fb682489b0172209281521f8ea88090409d5cf5a 100755 --- a/get_obj_dist/src/object_to_distance.py +++ b/get_obj_dist/src/object_to_distance.py @@ -1,6 +1,5 @@ #!/usr/bin/env python -import numpy as np import sys import cv2 import rospy @@ -17,6 +16,7 @@ font = cv2.FONT_HERSHEY_SIMPLEX font_scale = 0.75 font_color = (255, 255, 255) line_type = 2 +marker_size = 5 size_of_moving_avg = 15 @@ -25,16 +25,19 @@ class obj_dist: # Declare functional variables self.bridge = CvBridge() self.marker_array = MarkerArray() - self.moving_average = [3] * size_of_moving_avg - self.set_marker_array(5, 'camera_color_optical_frame', 'package://get_obj_dist/human_model.STL') - # Initializing ROS Topics + self.moving_average = [[3] * size_of_moving_avg] * marker_size + self.set_marker_array(marker_size, 'camera_color_optical_frame', 'package://get_obj_dist/human_model.STL') + + # Initiale publishers self.dist_pub = rospy.Publisher('/obj_to_dist/human_distance', Image, queue_size=10) self.render_pub = rospy.Publisher('/obj_to_dist/show_people_marker_array', MarkerArray, queue_size=10) + # Initialize subscribers self.bbx_sub = message_filters.Subscriber('/human_detected_image/bounding_box', box_list) self.human_image_sub = message_filters.Subscriber('/human_detected_image/image', Image) - self.depth_image_sub = message_filters.Subscriber('/camera/depth/image_rect_raw', Image) + self.depth_image_sub = message_filters.Subscriber('/camera/aligned_depth_to_color/image_raw', Image) + # self.depth_image_sub = message_filters.Subscriber('/camera/depth/image_rect_raw', Image) ts = message_filters.ApproximateTimeSynchronizer([self.bbx_sub, self.human_image_sub, self.depth_image_sub], @@ -43,6 +46,7 @@ class obj_dist: ts.registerCallback(self.callback) def callback(self, bbx, image, depth): + print('working lol') if bbx.length: cv_depth = self.bridge.imgmsg_to_cv2(depth, 'passthrough') cv_image = self.bridge.imgmsg_to_cv2(image, 'bgr8') @@ -57,12 +61,13 @@ class obj_dist: def get_human_distance(self, cv_depth, cv_image, box, person_id): roi_depth = cv_depth[box.ymin:box.ymax, box.xmin:box.xmax] - filtered_depth, _size = filter_background(roi_depth) + # filtered_depth, _size = filter_background(roi_depth) + filtered_depth, _size = dynamic_background(roi_depth) if _size: - self.moving_average.pop() - self.moving_average.insert(0, filtered_depth.sum() / _size / 1000.0) + self.moving_average[person_id].pop() + self.moving_average[person_id].insert(0, filtered_depth.sum() / _size / 1000.0) - current_avg = sum(self.moving_average) / size_of_moving_avg + current_avg = sum(self.moving_average[person_id]) / size_of_moving_avg x_meter = get_x_in_meters(box.xmin, box.xmax, current_avg) cv2.putText(cv_image, '{} meters / Person {}'.format(round(current_avg, 2), person_id), @@ -79,14 +84,13 @@ class obj_dist: return -1, -1, -1 def set_marker_array(self, size, frame_id, package): - # self.marker_array.markers = [Marker()] * size - for i in range(0, size): + for counter in range(0, size): self.marker_array.markers.append(Marker()) - self.marker_array.markers[i].header.frame_id = frame_id - self.marker_array.markers[i].lifetime = rospy.Duration() - self.marker_array.markers[i].id = i - self.marker_array.markers[i].type = Marker.MESH_RESOURCE - self.marker_array.markers[i].mesh_resource = package + self.marker_array.markers[counter].header.frame_id = frame_id + self.marker_array.markers[counter].lifetime = rospy.Duration() + self.marker_array.markers[counter].id = counter + self.marker_array.markers[counter].type = Marker.MESH_RESOURCE + self.marker_array.markers[counter].mesh_resource = package def set_model_coordinates(self, cood, person_id): self.marker_array.markers[person_id].header.stamp = rospy.Time.now() @@ -124,5 +128,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/get_obj_dist/src/depth_cam.py b/get_obj_dist/src/tune_depth.py similarity index 100% rename from get_obj_dist/src/depth_cam.py rename to get_obj_dist/src/tune_depth.py diff --git a/get_obj_dist/src/utils.py b/get_obj_dist/src/utils.py index 77a08112d0f50ba2d05f4c4138409f755abbb482..8d2a3a31a40f47b260b48563e44381acec56c8d4 100644 --- a/get_obj_dist/src/utils.py +++ b/get_obj_dist/src/utils.py @@ -1,12 +1,17 @@ import numpy as np +import matplotlib.pyplot as plt + +_noise_limit = 100 +_diff = 1000 +_bin = [i * _diff for i in range(0, 11)] # Really basic way of separating foreground and background. -def filter_background(roi): +def filter_background(roi, max_depth=8000): # Anything further than 8000mm, we consider it as background # Anything less than 100mm is consider noise - ret_val = np.ma.masked_greater(roi, 8000) - ret_val = np.ma.masked_less(ret_val, 100) + ret_val = np.ma.masked_greater(roi, max_depth) + ret_val = np.ma.masked_less(ret_val, _noise_limit) unique, counts = np.unique(ret_val.mask, return_counts=True) _dict = dict(zip(unique, counts)) if False in _dict: @@ -15,6 +20,19 @@ def filter_background(roi): return ret_val, 0 +def dynamic_background(roi): + # Anything less than 100mm is sure noise + # roi = np.ma.masked_less(roi, 100) + roi_1d = roi.flatten() + hist, bins = np.histogram(roi_1d, bins=_bin, density=True) + max_bin = hist.argmax() + 1 + + # plt.hist(roi_1d, bins=_bin, density=True) + # plt.title('Hello') + # plt.show() + return filter_background(roi, max_bin * _diff) + + def get_x_in_meters(xmin, xmax, z_i): # Tune z_c to get better value lol. # 500 is literally randomly chosen lol diff --git a/human_detection/launch/hdm_full.launch b/human_detection/launch/hdm_full.launch new file mode 100644 index 0000000000000000000000000000000000000000..a0d3db1c9fb62fad5f6fef2d54ebf00b918fe337 --- /dev/null +++ b/human_detection/launch/hdm_full.launch @@ -0,0 +1,4 @@ +<launch> + <node pkg="human_detection" type="webcam.py" name="webcam"/> + <node pkg="get_obj_dist" type="object_to_distance.py" name="object_to_distance"/> +</launch> \ No newline at end of file diff --git a/human_detection/src/reference.py b/human_detection/src/reference.py index a94bb1d56fd4ea924a1e152cb0fa9e322f399987..c9f45d7ac5037b57a75937ae382249902399ee21 100755 --- a/human_detection/src/reference.py +++ b/human_detection/src/reference.py @@ -8,43 +8,47 @@ from std_msgs.msg import String from sensor_msgs.msg import Image from cv_bridge import CvBridge, CvBridgeError + class image_converter: - def __init__(self): - self.image_pub = rospy.Publisher("image_topic_2",Image, queue_size=10) + def __init__(self): + self.image_pub = rospy.Publisher("image_topic_2", Image, queue_size=10) - self.bridge = CvBridge() - self.image_sub = rospy.Subscriber("/camera/color/image_raw",Image,self.callback) + self.bridge = CvBridge() + self.image_sub = rospy.Subscriber("/camera/color/image_raw", Image, self.callback) - def callback(self,data): - try: - cv_image = self.bridge.imgmsg_to_cv2(data, "bgr8") - - except CvBridgeError as e: - print(e) + def callback(self, data): + try: + cv_image = self.bridge.imgmsg_to_cv2(data, "bgr8") - (rows,cols,channels) = cv_image.shape - if cols > 60 and rows > 60 : - cv2.circle(cv_image, (50,50), 10, 255) + except CvBridgeError as e: + print(e) - cv2.imshow("Image window", cv_image) - cv2.waitKey(3) + (rows, cols, channels) = cv_image.shape + if cols > 60 and rows > 60: + cv2.circle(cv_image, (50, 50), 10, 255) + + cv2.imshow("Image window", cv_image) + cv2.waitKey(3) + + try: + ret_img = self.bridge.cv2_to_imgmsg(cv_image, "bgr8") + ret_img.header = data.header + print(rospy.Time.now()) + self.image_pub.publish(ret_img) + except CvBridgeError as e: + print(e) - try: - ret_img = self.bridge.cv2_to_imgmsg(cv_image, "bgr8") - ret_img.header = data.header - self.image_pub.publish(ret_img) - except CvBridgeError as e: - print(e) def main(args): - ic = image_converter() - rospy.init_node('image_converter', anonymous=True) - try: - rospy.spin() - except KeyboardInterrupt: - print("Shutting down") - cv2.destroyAllWindows() + ic = image_converter() + rospy.init_node('image_converter', anonymous=True) + try: + rospy.spin() + except KeyboardInterrupt: + print("Shutting down") + cv2.destroyAllWindows() + if __name__ == '__main__': - main(sys.argv) \ No newline at end of file + main(sys.argv) diff --git a/human_detection/src/webcam.py b/human_detection/src/webcam.py index f26ca35b6482da22ccf6df14c6f9aba2b4637fe7..1075dcd807a81bcfba40300c0995462bba627c16 100755 --- a/human_detection/src/webcam.py +++ b/human_detection/src/webcam.py @@ -68,7 +68,7 @@ class human_detector: self.image_sub = rospy.Subscriber("/camera/color/image_raw", Image, self.callback) self.image_pub = rospy.Publisher("/human_detected_image/image", Image, queue_size=10) - self.bbx_pub = rospy.Publisher('/human_detected_image/bounding_box', box_list, queue_size=10) + self.bbx_pub = rospy.Publisher("/human_detected_image/bounding_box", box_list, queue_size=10) def callback(self, data): t0 = time.time() @@ -126,7 +126,7 @@ class human_detector: counter = 0 list_length = 0 bbx_list = box_list() - bbx_list.header.stamp = rospy.Time.now() + bbx_list.header.stamp = data.header.stamp for score in scores[0]: if score > 0.6: @@ -145,12 +145,10 @@ class human_detector: try: cvt_msg = self.bridge.cv2_to_imgmsg(cv_image, "bgr8") - cvt_msg.header.stamp = rospy.Time.now() + cvt_msg.header.stamp = data.header.stamp self.image_pub.publish(cvt_msg) - # print(cvt_msg.header) except CvBridgeError as e: print(e) - # Append Accuracy # if scores[0][0] > 0.01: diff --git a/human_detection_demo.mp4 b/human_detection_demo.mp4 new file mode 100644 index 0000000000000000000000000000000000000000..57d2884ed18681a37ae14fefb84453876510cbf3 Binary files /dev/null and b/human_detection_demo.mp4 differ