Skip to content

Instantly share code, notes, and snippets.

@SteveMacenski
Created March 9, 2020 00:12
Show Gist options
  • Star 0 You must be signed in to star a gist
  • Fork 0 You must be signed in to fork a gist
  • Save SteveMacenski/a614dd99256347145fc043106b564a6c to your computer and use it in GitHub Desktop.
Save SteveMacenski/a614dd99256347145fc043106b564a6c to your computer and use it in GitHub Desktop.
Depth Camera Basic Characteristic Comparison
#!/usr/bin/env python
from __future__ import print_function
import roslib
import sys
import rospy
import cv2
from std_msgs.msg import String
import numpy
from sensor_msgs.msg import Image
import cv2
from cv_bridge import CvBridge, CvBridgeError
class depth_metrics:
def __init__(self):
self.image_sub = rospy.Subscriber("/camera/depth/image",Image,self.callback)
self.pts = []
self.bridge = CvBridge()
def callback(self,data):
cv_image = self.bridge.imgmsg_to_cv2(data, "passthrough")
middle_x = data.height / 2
middle_y = data.width / 2
pt = cv_image[middle_x][middle_y]
self.pts.append(pt)
if len(self.pts) > 1000:
print("Got 1000 samples")
print("Std: " + str(numpy.std(self.pts)))
print("Mean: " + str(numpy.mean(self.pts)))
print("Median: " + str(numpy.median(self.pts)))
print("Average: " + str(numpy.average(self.pts)))
rospy.signal_shutdown("complete.")
def main(args):
rospy.init_node('depth_metrics', anonymous=True)
ic = depth_metrics()
try:
rospy.spin()
except KeyboardInterrupt:
print("Shutting down")
if __name__ == '__main__':
main(sys.argv)
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment