2 from sensor_msgs.msg 
import Image 
as msg_Image
 
    3 from sensor_msgs.msg 
import CameraInfo
 
    4 from cv_bridge 
import CvBridge, CvBridgeError
 
    8 import pyrealsense2 
as rs2
 
    9 if (
not hasattr(rs2, 
'intrinsics')):
 
   10     import pyrealsense2.pyrealsense2 
as rs2
 
   13     def __init__(self, depth_image_topic, depth_info_topic):
 
   17         confidence_topic = depth_image_topic.replace(
'depth', 
'confidence')
 
   25             cv_image = self.
bridge.imgmsg_to_cv2(data, data.encoding)
 
   27             indices = np.array(np.where(cv_image == cv_image[cv_image > 0].min()))[:,0]
 
   28             pix = (indices[1], indices[0])
 
   30             line = 
'\rDepth at pixel(%3d, %3d): %7.1f(mm).' % (pix[0], pix[1], cv_image[pix[1], pix[0]])
 
   33                 depth = cv_image[pix[1], pix[0]]
 
   34                 result = rs2.rs2_deproject_pixel_to_point(self.
intrinsics, [pix[0], pix[1]], depth)
 
   35                 line += 
'  Coordinate: %8.2f %8.2f %8.2f.' % (result[0], result[1], result[2])
 
   39             sys.stdout.write(line)
 
   42         except CvBridgeError 
as e:
 
   45         except ValueError 
as e:
 
   50             cv_image = self.
bridge.imgmsg_to_cv2(data, data.encoding)
 
   51             grades = np.bitwise_and(cv_image >> 4, 0x0f)
 
   54         except CvBridgeError 
as e:
 
   71             if cameraInfo.distortion_model == 
'plumb_bob':
 
   72                 self.
intrinsics.model = rs2.distortion.brown_conrady
 
   73             elif cameraInfo.distortion_model == 
'equidistant':
 
   74                 self.
intrinsics.model = rs2.distortion.kannala_brandt4
 
   75             self.
intrinsics.coeffs = [i 
for i 
in cameraInfo.D]
 
   76         except CvBridgeError 
as e:
 
   81     depth_image_topic = 
'/camera/depth/image_rect_raw' 
   82     depth_info_topic = 
'/camera/depth/camera_info' 
   85     print (
'show_center_depth.py')
 
   86     print (
'--------------------')
 
   87     print (
'App to demontrate the usage of the /camera/depth topics.')
 
   89     print (
'Application subscribes to %s and %s topics.' % (depth_image_topic, depth_info_topic))
 
   90     print (
'Application then calculates and print the range to the closest object.')
 
   91     print (
'If intrinsics data is available, it also prints the 3D location of the object')
 
   92     print (
'If a confedence map is also available in the topic %s, it also prints the confidence grade.' % depth_image_topic.replace(
'depth', 
'confidence'))
 
   98 if __name__ == 
'__main__':
 
   99     node_name = os.path.basename(sys.argv[0]).split(
'.')[0]
 
  100     rospy.init_node(node_name)