Path: blob/master/libraries/AP_Camera/examples/gst_rtsp_to_wx.py
9821 views
""""1Capture a RTSP video stream and display in wxpython23Usage4-----561. rtsp server78python ./gst_rtsp_server.py9103. display in wxpython1112python ./gst_rtsp_to_wx.py1314Acknowledgments15---------------1617Video class to capture GStreamer frames18https://www.ardusub.com/developers/opencv.html1920ImagePanel class to display openCV images in wxWidgets21https://stackoverflow.com/questions/14804741/opencv-integration-with-wxpython22"""2324# flake8: noqa2526import copy27import cv228import gi29import numpy as np30import threading31import wx323334gi.require_version("Gst", "1.0")35from gi.repository import Gst363738class VideoStream:39"""BlueRov video capture class constructor - adapted to capture rtspsrc4041Attributes:42address (string): RTSP address43port (int): RTSP port44mount_point (string): video stream mount point45video_decode (string): Transform YUV (12bits) to BGR (24bits)46video_pipe (object): GStreamer top-level pipeline47video_sink (object): Gstreamer sink element48video_sink_conf (string): Sink configuration49video_source (string): Udp source ip and port50latest_frame (np.ndarray): Latest retrieved video frame51"""5253def __init__(54self, address="127.0.0.1", port=8554, mount_point="/camera", latency=5055):56Gst.init(None)5758self.address = address59self.port = port60self.mount_point = mount_point61self.latency = latency6263self.latest_frame = self._new_frame = None6465self.video_source = (66f"rtspsrc location=rtsp://{address}:{port}{mount_point} latency={latency}"67)6869# Python does not have nibble, convert YUV nibbles (4-4-4) to OpenCV standard BGR bytes (8-8-8)70self.video_decode = (71"! decodebin ! videoconvert ! video/x-raw,format=(string)BGR ! videoconvert"72)73# Create a sink to get data74self.video_sink_conf = (75"! appsink emit-signals=true sync=false max-buffers=2 drop=true"76)7778self.video_pipe = None79self.video_sink = None8081self.run()8283def start_gst(self, config=None):84""" Start gstreamer pipeline and sink85Pipeline description list e.g:86[87'videotestsrc ! decodebin', \88'! videoconvert ! video/x-raw,format=(string)BGR ! videoconvert',89'! appsink'90]9192Args:93config (list, optional): Gstreamer pileline description list94"""9596if not config:97config = [98"videotestsrc ! decodebin",99"! videoconvert ! video/x-raw,format=(string)BGR ! videoconvert",100"! appsink",101]102103command = " ".join(config)104self.video_pipe = Gst.parse_launch(command)105self.video_pipe.set_state(Gst.State.PLAYING)106self.video_sink = self.video_pipe.get_by_name("appsink0")107108@staticmethod109def gst_to_opencv(sample):110"""Transform byte array into np array111112Args:113sample (TYPE): Description114115Returns:116TYPE: Description117"""118buf = sample.get_buffer()119caps_structure = sample.get_caps().get_structure(0)120array = np.ndarray(121(caps_structure.get_value("height"), caps_structure.get_value("width"), 3),122buffer=buf.extract_dup(0, buf.get_size()),123dtype=np.uint8,124)125return array126127def frame(self):128"""Get Frame129130Returns:131np.ndarray: latest retrieved image frame132"""133if self.frame_available:134self.latest_frame = self._new_frame135# reset to indicate latest frame has been 'consumed'136self._new_frame = None137return self.latest_frame138139def frame_available(self):140"""Check if a new frame is available141142Returns:143bool: true if a new frame is available144"""145return self._new_frame is not None146147def run(self):148"""Get frame to update _new_frame"""149150self.start_gst(151[152self.video_source,153self.video_decode,154self.video_sink_conf,155]156)157158self.video_sink.connect("new-sample", self.callback)159160def callback(self, sink):161sample = sink.emit("pull-sample")162self._new_frame = self.gst_to_opencv(sample)163164return Gst.FlowReturn.OK165166167class ImagePanel(wx.Panel):168def __init__(self, parent, video_stream, fps=30):169wx.Panel.__init__(self, parent)170171self._video_stream = video_stream172173# Shared between threads174self._frame_lock = threading.Lock()175self._latest_frame = None176177print("Waiting for video stream...")178waited = 0179while not self._video_stream.frame_available():180waited += 1181print("\r Frame not available (x{})".format(waited), end="")182cv2.waitKey(30)183print("\nSuccess! Video stream available")184185if self._video_stream.frame_available():186# Only retrieve and display a frame if it's new187frame = copy.deepcopy(self._video_stream.frame())188189# Frame size190height, width, _ = frame.shape191192parent.SetSize((width, height))193frame = cv2.cvtColor(frame, cv2.COLOR_BGR2RGB)194195self.bmp = wx.Bitmap.FromBuffer(width, height, frame)196197self.timer = wx.Timer(self)198self.timer.Start(int(1000 / fps))199200self.Bind(wx.EVT_PAINT, self.OnPaint)201self.Bind(wx.EVT_TIMER, self.NextFrame)202203def OnPaint(self, evt):204dc = wx.BufferedPaintDC(self)205dc.DrawBitmap(self.bmp, 0, 0)206207def NextFrame(self, event):208if self._video_stream.frame_available():209frame = copy.deepcopy(self._video_stream.frame())210211# Convert frame to bitmap for wxFrame212frame = cv2.cvtColor(frame, cv2.COLOR_BGR2RGB)213self.bmp.CopyFromBuffer(frame)214self.Refresh()215216217def main():218219# create the video stream220video_stream = VideoStream(mount_point="/camera")221222# app must run on the main thread223app = wx.App()224wx_frame = wx.Frame(None)225226# create the image panel227image_panel = ImagePanel(wx_frame, video_stream, fps=30)228229wx_frame.Show()230app.MainLoop()231232233if __name__ == "__main__":234main()235236237