diff --git a/.gitignore b/.gitignore index 47ce3ebd917badd70fa9653351ef29cc3a0a1d0b..30bd60effde2c708c3b453273a5e4bb684859502 100644 --- a/.gitignore +++ b/.gitignore @@ -1,4 +1,6 @@ .idea *.bag +*.pyc .catkin_workspace + # *CMakeLists.txt \ No newline at end of file diff --git a/README.md b/README.md index 89757aac7a30217f1f7bd88f262fdb2e2e09a593..de6da4d61f11520b9e66792b94cb9f415939c98e 100644 --- a/README.md +++ b/README.md @@ -4,6 +4,7 @@ Human detection model that runs on ROS This is a human detection mode that uses Intel RealSense D435 Camera and ROS Kinetic. Visit the GitHub page of Intel RealSense-ROS for more camera installation. +## Installing The Workspace Run the following commands on terminal to get started. First we start a workspace @@ -21,3 +22,22 @@ source ./devel/setup.bash ``` *Something like that. I will fix it later.* + +## Sample Data Files +Below are some links to example files. These bag files are too big for GitHub so I put them on Google Drive. +Download them as you wish. Here are the types and the message topics. +I recorded them with Intel RealSense D435 Camera at 60 fps (I think). + +``` +types: sensor_msgs/Image [060021388200f6f0f447d0fcd9c64743] + sensor_msgs/PointCloud2 [1158d486dd51d683ce2f1be655c3c181] +topics: /camera/color/image_raw 534 msgs : sensor_msgs/Image + /camera/depth/image_rect_raw 534 msgs : sensor_msgs/Image + /camera/depth_registered/points 525 msgs : sensor_msgs/PointCloud2 +``` + +1. Indoor settings +- *Will update as I go* + +2. Outdoor settings +- *Will update as I go* \ No newline at end of file diff --git a/get_obj_dist/src/depth_filter.py b/get_obj_dist/src/depth_filter.py index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..d9f30740377d389266d789106ded182b56c3b6d2 100644 --- a/get_obj_dist/src/depth_filter.py +++ b/get_obj_dist/src/depth_filter.py @@ -0,0 +1,13 @@ +import numpy.ma as ma +import cv2 + + +def filter_background(roi): + ret_val = ma.masked_less(roi, 2900) + # roi[roi <= 2900] + return ret_val + + +def mask_the_thing(image, mask): + cv2.bitwise_and(image, mask) + diff --git a/get_obj_dist/src/object_to_distance.py b/get_obj_dist/src/object_to_distance.py index 286d7229a45ed065555d9d43f2f955d0dbcf339d..1c0468a085617e412f9fa0386af87e00c3f7812c 100755 --- a/get_obj_dist/src/object_to_distance.py +++ b/get_obj_dist/src/object_to_distance.py @@ -6,12 +6,11 @@ import cv2 import rospy import message_filters -sys.path.append('/home/jerry/Documents/workspaces/ROS_human_detection/src/human_detection') - from visualization_msgs.msg import Marker from sensor_msgs.msg import Image, PointCloud2 from cv_bridge import CvBridge, CvBridgeError -from human_detection.msg import bounding_box, box_list +from human_detection.msg import box_list +from depth_filter import * text_position = (10, 50) font = cv2.FONT_HERSHEY_SIMPLEX @@ -19,43 +18,48 @@ font_scale = 0.75 font_color = (255, 255, 255) line_type = 2 + class obj_dist: def __init__(self): # Initializing ROS Topics self.bridge = CvBridge() self.dist_pub = rospy.Publisher('/obj_to_dist/human_distance', Image, queue_size=10) self.render_pub = rospy.Publisher('/obj_to_dist/render_human', Marker, queue_size=10) - - # self.bbx_sub = rospy.Subscriber('/human_detected_image/bounding_box', box_list, self.yea) - # self.human_image_sub = rospy.Subscriber('/human_detected_image/image', Image, self.yea1) - # self.depth_image_sub = rospy.Subscriber('/camera/depth/image_rect_raw', Image, self.yea2) + self.roi_pub = rospy.Publisher('/obj_to_dist/disappera', Image, queue_size=10) 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.pcl_sub = message_filters.Subscriber('/camera/depth_registered/points', PointCloud2) + # self.pcl_sub = message_filters.Subscriber('/camera/depth_registered/points', PointCloud2) ts = message_filters.ApproximateTimeSynchronizer([self.bbx_sub, self.human_image_sub, - self.depth_image_sub, self.pcl_sub], + self.depth_image_sub], queue_size=10, slop=1) ts.registerCallback(self.callback) - def callback(self, bbx, image, depth, point_cloud): + def callback(self, bbx, image, depth): if bbx.length: cv_depth = self.bridge.imgmsg_to_cv2(depth, 'passthrough') cv_image = self.bridge.imgmsg_to_cv2(image, 'bgr8') + for box in bbx.people_list: cood = self.get_human_distance(cv_depth, cv_image, box) - self.render_human(cood, point_cloud) + self.render_human(cood) def get_human_distance(self, cv_depth, cv_image, box): - roi_depth = cv_depth[box.xmin:box.xmax, box.ymin:box.ymax] + roi_depth = cv_depth[box.ymin:box.ymax, box.xmin:box.xmax] - filtered_depth = roi_depth[roi_depth <= 2900] + jk = np.shape(roi_depth) + jk = jk[0]*jk[1] + filtered_depth = filter_background(roi_depth) _size = len(filtered_depth) + print('size of original: {}'.format(jk)) + print('size of filtered: {}'.format(_size)) + print('') avg_distance = filtered_depth.sum() / _size / 1000 + x_meter = self.get_x_in_meters(box.xmin, box.xmax, avg_distance) cv2.putText(cv_image, '{} meters'.format(avg_distance), (box.xmin, box.ymax - 100), @@ -63,10 +67,14 @@ class obj_dist: font_scale, font_color, line_type) + + # self.roi_pub.publish(self.bridge.cv2_to_imgmsg(filtered_depth.data)) + self.roi_pub.publish(self.bridge.cv2_to_imgmsg(roi_depth)) self.dist_pub.publish(self.bridge.cv2_to_imgmsg(cv_image)) + return x_meter, 0, avg_distance - def render_human(self, cood, point_cloud): + def render_human(self, cood): marker = Marker() marker.header.frame_id = 'camera_color_optical_frame' marker.header.stamp = rospy.Time.now() @@ -103,6 +111,7 @@ class obj_dist: def main(args): rospy.init_node('obj_dist', anonymous=True) + print("object_to_distance.py is running") _ = obj_dist() rospy.spin() cv2.destroyAllWindows() diff --git a/human_detection/src/analysis_tools/__init__.pyc b/human_detection/src/analysis_tools/__init__.pyc deleted file mode 100644 index 0e12914e3a930712c2de649653086656463758b6..0000000000000000000000000000000000000000 Binary files a/human_detection/src/analysis_tools/__init__.pyc and /dev/null differ diff --git a/human_detection/src/analysis_tools/data_grapher.pyc b/human_detection/src/analysis_tools/data_grapher.pyc deleted file mode 100644 index 3ebfd56856e2465a9fc8f2bc5a9750dd3c372be1..0000000000000000000000000000000000000000 Binary files a/human_detection/src/analysis_tools/data_grapher.pyc and /dev/null differ diff --git a/human_detection/src/analysis_tools/define.pyc b/human_detection/src/analysis_tools/define.pyc deleted file mode 100644 index f56fc3a6ed9894a444dcdadfa3a44b25d16ba6cd..0000000000000000000000000000000000000000 Binary files a/human_detection/src/analysis_tools/define.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/__init__.pyc b/human_detection/src/object_detection/__init__.pyc deleted file mode 100644 index 3a96288dc3006c1b4e2a8c9418360b3e30f0fc8f..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/__init__.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/core/__init__.pyc b/human_detection/src/object_detection/core/__init__.pyc deleted file mode 100644 index 4334ba3f73ce0f5b79d1cacc17ad0f6e402b1c41..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/core/__init__.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/core/__pycache__/__init__.cpython-35.pyc b/human_detection/src/object_detection/core/__pycache__/__init__.cpython-35.pyc deleted file mode 100644 index 524b7f51252d289ac9f0fb435af19f5e950b22e7..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/core/__pycache__/__init__.cpython-35.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/core/__pycache__/standard_fields.cpython-35.pyc b/human_detection/src/object_detection/core/__pycache__/standard_fields.cpython-35.pyc deleted file mode 100644 index 2ed183ec890c235cc67700097cf4888661c1e33f..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/core/__pycache__/standard_fields.cpython-35.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/core/standard_fields.pyc b/human_detection/src/object_detection/core/standard_fields.pyc deleted file mode 100644 index 2c2592ebff01bd41323956b0f7fb48b5adc15c3d..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/core/standard_fields.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/protos/__init__.pyc b/human_detection/src/object_detection/protos/__init__.pyc deleted file mode 100644 index 2c2947fe2a190c1af052c50146e4bc8cb4cac982..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/protos/__init__.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/protos/__pycache__/__init__.cpython-35.pyc b/human_detection/src/object_detection/protos/__pycache__/__init__.cpython-35.pyc deleted file mode 100644 index ebc6e63cf446c3a204a9cb1a644da7f144b061ec..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/protos/__pycache__/__init__.cpython-35.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/protos/__pycache__/string_int_label_map_pb2.cpython-35.pyc b/human_detection/src/object_detection/protos/__pycache__/string_int_label_map_pb2.cpython-35.pyc deleted file mode 100644 index 9fe9ef2b70e59302fd92420b44e65d9a6d89a44c..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/protos/__pycache__/string_int_label_map_pb2.cpython-35.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/protos/string_int_label_map_pb2.pyc b/human_detection/src/object_detection/protos/string_int_label_map_pb2.pyc deleted file mode 100644 index 010fc10b21fd25287e6451a84d7e71c582b6547d..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/protos/string_int_label_map_pb2.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/utils/__init__.pyc b/human_detection/src/object_detection/utils/__init__.pyc deleted file mode 100644 index 7d4cc5c46ea1c5752f419da6a629f152bebeec00..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/utils/__init__.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/utils/__pycache__/__init__.cpython-35.pyc b/human_detection/src/object_detection/utils/__pycache__/__init__.cpython-35.pyc deleted file mode 100644 index 51e4e2ab8539bd3c2e00145651e2000e3849f045..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/utils/__pycache__/__init__.cpython-35.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/utils/__pycache__/label_map_util.cpython-35.pyc b/human_detection/src/object_detection/utils/__pycache__/label_map_util.cpython-35.pyc deleted file mode 100644 index f4641acb592d242c3dcb36077ad26c4175e54cc4..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/utils/__pycache__/label_map_util.cpython-35.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/utils/__pycache__/ops.cpython-35.pyc b/human_detection/src/object_detection/utils/__pycache__/ops.cpython-35.pyc deleted file mode 100644 index c09cb2ddc4014845e521ae2fb1abc560b098bc71..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/utils/__pycache__/ops.cpython-35.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/utils/__pycache__/shape_utils.cpython-35.pyc b/human_detection/src/object_detection/utils/__pycache__/shape_utils.cpython-35.pyc deleted file mode 100644 index 8daff5d5cecff15fc929cc8549b45fac1611bd48..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/utils/__pycache__/shape_utils.cpython-35.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/utils/__pycache__/spatial_transform_ops.cpython-35.pyc b/human_detection/src/object_detection/utils/__pycache__/spatial_transform_ops.cpython-35.pyc deleted file mode 100644 index a7ed2921a1101c8993b5a6a334558174f1920ae2..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/utils/__pycache__/spatial_transform_ops.cpython-35.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/utils/__pycache__/static_shape.cpython-35.pyc b/human_detection/src/object_detection/utils/__pycache__/static_shape.cpython-35.pyc deleted file mode 100644 index be76c11259bfe7ab44470c243b4ef9fca961e26a..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/utils/__pycache__/static_shape.cpython-35.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/utils/__pycache__/visualization_utils.cpython-35.pyc b/human_detection/src/object_detection/utils/__pycache__/visualization_utils.cpython-35.pyc deleted file mode 100644 index ce0b4b812d14fd98514894353f50633fb6154dd2..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/utils/__pycache__/visualization_utils.cpython-35.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/utils/label_map_util.pyc b/human_detection/src/object_detection/utils/label_map_util.pyc deleted file mode 100644 index 1e1915c0da92ae2c7dcb4fda0c95ff8edefd5025..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/utils/label_map_util.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/utils/shape_utils.pyc b/human_detection/src/object_detection/utils/shape_utils.pyc deleted file mode 100644 index 0835005030bc9c22d6692e77061a1979cbffe068..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/utils/shape_utils.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/utils/static_shape.pyc b/human_detection/src/object_detection/utils/static_shape.pyc deleted file mode 100644 index 136332d30b697bd81b354f502d691bc52b436b23..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/utils/static_shape.pyc and /dev/null differ diff --git a/human_detection/src/object_detection/utils/visualization_utils.pyc b/human_detection/src/object_detection/utils/visualization_utils.pyc deleted file mode 100644 index 11a511e5b62a0ad7e6410cd566534b95b322b7dd..0000000000000000000000000000000000000000 Binary files a/human_detection/src/object_detection/utils/visualization_utils.pyc and /dev/null differ diff --git a/human_detection/src/webcam.py b/human_detection/src/webcam.py index d333adcce793a906074c860d2ac8b6ea15bcfd4a..f26ca35b6482da22ccf6df14c6f9aba2b4637fe7 100755 --- a/human_detection/src/webcam.py +++ b/human_detection/src/webcam.py @@ -3,13 +3,13 @@ import time import sys import os import rospy -from setuptools import setup, find_packages +import numpy as np import tensorflow as tf sys.path.append('/home/jerry/Documents/workspaces/human_detection/src/ROS_human_detection/human_detection/src') # For performance analysis timing, import time. -from analysis_tools.data_grapher import * +# from analysis_tools.data_grapher import * from analysis_tools.define import * from human_detection.msg import bounding_box, box_list from sensor_msgs.msg import Image