RaspberryPi Zero 2w

Raspberry Pi Zero 2w로 구현하는 CCTV

연결 구성도

 

image.png

Start and Stop Shell

Start and Stop Shell 

 

Start Shell

#!/bin/bash

echo
echo '##### START KKo KKo Rack #####'
echo

wpa_cli -i wlan0 status 
echo
echo

FILENAME=/home/hyunsu/work/nohup.out
if [ -f "$FILENAME" ] ; then
	echo "nohup.out delete !"
	rm /home/hyunsu/work/opencv/nohup.out
else
	echo "file not exist"
fi

echo '##### START CCTV #####'
cd /home/hyunsu/work/opencv
nohup python3 /home/hyunsu/work/opencv/serverUsb.py &  

echo '##### START BROD SOUND #####'
nohup cvlc -vvv alsa://plughw:1 --sout '#transcode{acodec=mp3,ab=64,channels=1}:standard{access=http,dst=0.0.0.0:8080/out.mp3}' 1> /dev/null 2>&1 & 


echo
echo '##### STARTed KKo KKo Rack #####'
echo



Stop Shell

#!/bin/bash

echo
echo '##### STOP  KKo KKo Rack #####'
echo


ps -ef | grep stepperMoter.py | grep -v grep
KILLPID=`ps -ef | grep serverUsb.py | grep -v grep | awk '{print($2)}'`
echo "Stop CCTV Process = " $KILLPID
kill -9 $KILLPID


ps -ef | grep vlc | grep -v grep
KILLPID=`ps -ef | grep vlc | grep -v grep | awk '{print($2)}'`
echo "Stop Brod Sound Process = " $KILLPID
kill -9 $KILLPID

echo
echo '##### STOPed KKo KKo Rack #####'
echo

 

Main Python 프로그램 [serverUsb.py]

Main Python 프로그램 

serverUsb.py

from flask import Flask, render_template, send_from_directory, Response, request, send_file
# from flask_socketio import SocketIO
from pathlib import Path
from capture import capture_and_save
from usbwebcamera import UsbWebCamera
import argparse, logging, logging.config, conf
import os
from gpioControl import GpioControl
from listenSpeech import ListenSpeech
from urllib.parse import parse_qs

gpio = GpioControl()
archive_path = os.path.join(os.path.dirname(os.path.realpath(__file__)), 'archive')
listenspeech = ListenSpeech()

logging.config.dictConfig(conf.dictConfig)
logger = logging.getLogger(__name__)

usbcamera = UsbWebCamera(20,0)
usbcamera.run()


app = Flask(__name__)
#app.static_url_path = '/home/pi/Work/opencv/templates'
# app.config["SECRET_KEY"] = "secret!"
# socketio = SocketIO(app)

@app.after_request
def add_header(r):
    """
    Add headers to both force latest IE rendering or Chrome Frame,
    and also to cache the rendered page for 10 minutes
    """
    r.headers["Cache-Control"] = "no-cache, no-store, must-revalidate"
    r.headers["Pragma"] = "no-cache"
    r.headers["Expires"] = "0"
    r.headers["Cache-Control"] = "public, max-age=0"
    return r


@app.route("/")
def entrypoint1():
    logger.debug("Requested /")
    return render_template("index.html")

@app.route("/index.html")
def entrypoint2():
    logger.debug("Requested /")
    return render_template("index.html")

@app.route("/msg", methods=['GET', 'POST'])
def msg():
     if request.method == 'POST':
        message = request.form['textinput'] 
        if not message :
             reString = "No received message"
        else :
             reString = listenspeech.speech(message)
        print("Get Message = " + reString)
     return reString
     
@app.route("/usbcapture")
def captureusb():
    logger.debug("Requested capture")
    im = usbcamera.get_frame(_bytes=False)
    capture_and_save(im)
    return render_template("send_to_init.html")

@app.route('/archive')
def archive():
    return render_template('archive.html')

def get_type(filename):
    name, extension = os.path.splitext(filename)
    return 'video' if extension == '.mp4' else 'audio' if extension == '.wav' else 'audio' if extension == '.mp3' else 'photo'

@app.route('/archive/<string:filename>')
def archive_item(filename):
    name, extension = os.path.splitext(filename)
    type = get_type(filename)
    return render_template('record.html', filename=filename, type=type)

@app.route('/archive/delete/<string:filename>')
def archive_delete(filename):
    os.remove(archive_path + "/" + filename)
    return redirect(url_for('archive'))

@app.route('/archive/play/<string:filename>')
def archive_play(filename):
    return send_file('archive/' + filename)

def get_records():
    records = []

    for filename in sorted(os.listdir(archive_path), reverse=True):
        if not filename.startswith('.'):
            type = get_type(filename)
            size = byte_to_mb(os.path.getsize(archive_path + "/" + filename))
            record = {"filename": filename, 'size': size, 'type': type}
            records.append(record)

    return records
    
def byte_to_mb(byte):
    mb = "{:.2f}".format(byte / 1024 / 1024)
    return str(mb) + " MB"

app.jinja_env.globals.update(get_records=get_records)

    
@app.route("/archive/last")
def last_image():
    logger.debug("Requested last image")
    p = Path("archive/last.png")
    if p.exists():
        r = "last.png"
    else:
        logger.debug("No last image")
        r = "not_found.jpeg"
    return send_from_directory("archive",r)


def genusb(usbcamera):
    logger.debug("Starting USB stream")
    while True:
        frame = usbcamera.get_frame()
        yield (b'--frame\r\n'
               b'Content-Type: image/png\r\n\r\n' + frame + b'\r\n')
        
@app.route("/stream")
def stream_page():
    logger.debug("Requested stream page")
    return render_template("stream.html")

@app.route("/video_usb_feed")
def video_usb_feed():
    return Response(genusb(usbcamera),
        mimetype="multipart/x-mixed-replace; boundary=frame")

@app.route("/temperature")
def temperature():
    content = os.popen("vcgencmd measure_temp").readline()
    content = content.replace("temp=", "")
    return Response(content, mimetype='text/xml')



''' ##### Control Camera Section ##### '''
@app.route("/shooting", methods=['GET', 'POST'])
def shooting():
    reString = "Shooting : " + gpio.shooting()
    return Response(reString, mimetype='text/html')

@app.route("/init")
def init():
    reString = "Camera position init : " + gpio.initMotorPosition()
    print("Move init ...")
    return Response(reString, mimetype='text/html')

@app.route("/up")
def up():
    reString = gpio.moveUp()
    print("Move Up ...")
    return Response(reString, mimetype='text/html')
    
@app.route("/down")
def down():
    reString = gpio.moveDown()
    print("Move Down ...")
    return Response(reString, mimetype='text/html')

@app.route("/left")
def left():
    reString = gpio.moveLeft()
    print("Move Left ...")
    return Response(reString, mimetype='text/html')

@app.route("/right")
def right():
    reString = gpio.moveRight()
    print("Move Right ...")
    return Response(reString, mimetype='text/html')

''' ##### Caterpillar Tracks ##### '''
@app.route("/forward", methods=['GET', 'POST'])
def forward():
    if request.method == 'POST':
        moveOrder = request.form['moveCnt']
        if not moveOrder :
            reString = "Do not move"
        else :
            reString = gpio.goForward(moveOrder)
        print("Go Forward ...("+moveOrder+")")
    return reString

@app.route("/backward", methods=['GET', 'POST'])
def backward():
    if request.method == 'POST':
        moveOrder = request.form['moveCnt']
        if not moveOrder :
            reString = "Do not move"
        else :
            reString = gpio.goBackward(moveOrder)
        print("Go Backward ...("+moveOrder+")")
    return reString

@app.route("/turnleftback", methods=['GET', 'POST'])
def turnleftback():
    if request.method == 'POST':
        moveOrder = request.form['moveCnt']
        if not moveOrder :
            reString = "Do not move"
        else :
            reString = gpio.goTurnleftback(moveOrder)
        print("Go Turn Left back...("+moveOrder+")")
    return reString

@app.route("/turnrightback", methods=['GET', 'POST'])
def turnrightback():
    if request.method == 'POST':
        moveOrder = request.form['moveCnt']
        if not moveOrder :
            reString = "Do not move"
        else :
            reString = gpio.goTurnrightback(moveOrder)
        print("Go Turn Right back...("+moveOrder+")")
    return reString

@app.route("/turnleftforward", methods=['GET', 'POST'])
def turnleftforward():
    if request.method == 'POST':
        moveOrder = request.form['moveCnt']
        if not moveOrder :
            reString = "Do not move"
        else :
            reString = gpio.goTurnleftforward(moveOrder)
        print("Go Turn Left forward...("+moveOrder+")")
    return reString

@app.route("/turnrightforward", methods=['GET', 'POST'])
def turnrightforward():
    if request.method == 'POST':
        moveOrder = request.form['moveCnt']
        if not moveOrder :
            reString = "Do not move"
        else :
            reString = gpio.goTurnrightforward(moveOrder)
        print("Go Turn Right forward...("+moveOrder+")")
    return reString

 
    

if __name__=="__main__":
    # socketio.run(app,host="0.0.0.0",port="3005",threaded=True)
    parser = argparse.ArgumentParser()
    parser.add_argument('-p','--port',type=int,default=8081, help="Running port")
    parser.add_argument("-H","--host",type=str,default='0.0.0.0', help="Address to broadcast")
    args = parser.parse_args()
    logger.debug("Starting server")
    #app.run(host=args.host, port=args.port, threaded=True, debug=True)
    app.run(host=args.host, port=args.port, threaded=True)

USB Camera [usbwebcamera.py]

usbwebcamera.py

import cv2
import threading
import time
import logging
import os

logger = logging.getLogger(__name__)
archive_path = os.path.join(os.path.dirname(os.path.realpath(__file__)), 'archive')

thread = None

class UsbWebCamera:

    def __init__(self,fps=20,video_source=1):
        logger.info("Initializing usb camera class with {fps} " + str(fps) + " and video_source={" + str(video_source) + "}")
        self.fps = fps
        self.video_source = video_source
        self.camera = cv2.VideoCapture(self.video_source)
        print( "1: width: {}, height : {}".format(self.camera.get(3), self.camera.get(4) ) )
        #width=self.camera.get(cv2.CAP_PROP_FRAME_WIDTH)
        #height=self.camera.get(cv2.CAP_PROP_FRAME_HEIGHT)
        #print( "2: width: {}, height : {}".format(width, height) )
        self.camera.set(cv2.CAP_PROP_FRAME_WIDTH, 640)
        self.camera.set(cv2.CAP_PROP_FRAME_HEIGHT, 480)
        
        # We want a max of 5s history to be stored, thats 5s*fps
        self.max_frames = 5*self.fps
        self.frames = []
        self.isrunning = False
        
    def run(self):
        logging.debug("Perparing Usb Camera thread")
        global thread
        if thread is None:
            logging.debug("Creating thread")
            thread = threading.Thread(target=self._capture_loop,daemon=True)
            logger.debug("Starting thread")
            self.isrunning = True
            thread.start()
            logger.info("Thread started")

    def _capture_loop(self):
        dt = 1/self.fps
        logger.debug("Observation started")
        while self.isrunning:
            v,im = self.camera.read()
            #im = cv2.flip(im, 1)
            #im = cv2.flip(im, 0)
            if v:
                if len(self.frames)==self.max_frames:
                    self.frames = self.frames[1:]
                self.frames.append(im)
            time.sleep(dt)
        logger.info("Thread stopped successfully")

    def stop(self):
        logger.debug("Stopping thread")
        self.isrunning = False
        
    def get_frame(self, _bytes=True):
        if len(self.frames)>0:
            if _bytes:
                img = cv2.imencode('.png',self.frames[-1])[1].tobytes()
            else:
                img = self.frames[-1]
        else:
            with open(archive_path+"/not_found.jpeg","rb") as f:
                img = f.read()
        return img
        

GPIO 프로그램 [gpioControl.py]

gpioControl.py


import RPi.GPIO as GPIO
from time import sleep

ina1 = 33
ina2 = 35
ena = 37

inb1 = 31
inb2 = 29
enb = 23

fire = 16 

UpDownCam=12
RightLeftCam=18

GPIO.setmode(GPIO.BOARD)

GPIO.setup(UpDownCam, GPIO.OUT, initial=1)
GPIO.setup(RightLeftCam, GPIO.OUT, initial=1)
GPIO.setup(11, GPIO.OUT, initial=1) # light

GPIO.setup(ina1,GPIO.OUT)
GPIO.setup(ina2,GPIO.OUT)
GPIO.setup(ena,GPIO.OUT)

GPIO.setup(inb1,GPIO.OUT)
GPIO.setup(inb2,GPIO.OUT)
GPIO.setup(enb,GPIO.OUT)

p1 = GPIO.PWM(RightLeftCam, 50)  # 50 Hz
p2 = GPIO.PWM(UpDownCam, 50)  # 50
p1.start(0)
p2.start(0)
p1.ChangeDutyCycle(0)
p2.ChangeDutyCycle(0)

pa=GPIO.PWM(ena,1000)
pa.start(25)

pb=GPIO.PWM(enb,1000)
pb.start(25)

initVerticalVal = 6.9
initHorizontalVal = 6.6

verticalVal = initVerticalVal
horizontalVal = initHorizontalVal

cameraPositionX = initVerticalVal
cameraPositionY = initHorizontalVal

# Set up camera constants
IM_WIDTH = 640
IM_HEIGHT = 480


class GpioControl(object):

    def __init__(self):
        global verticalVal
        global horizontalVal
        global p1
        global p2
        p1.ChangeDutyCycle(verticalVal)
        p2.ChangeDutyCycle(horizontalVal)
        sleep(0.1)
        p1.ChangeDutyCycle(0)
        p2.ChangeDutyCycle(0)
        print("> Init Vert=" + str(verticalVal) + ",Hort=" + str(horizontalVal))
   
    def click(self):
        GPIO.output(11, GPIO.LOW)
        sleep(0.5)
        GPIO.output(11, GPIO.HIGH)
        sleep(1)

    def __del__(self):
        global p1
        global p2
        p1.stop()
        p2.stop()
        print(" GPIO.__del__() ")
        GPIO.cleanup()

    def startUp(self):
        GPIO.setmode(GPIO.BOARD)
        GPIO.setup(UpDownCam, GPIO.OUT, initial=1)
        GPIO.setup(RightLeftCam, GPIO.OUT, initial=1)

        GPIO.setup(ina1,GPIO.OUT)
        GPIO.setup(ina2,GPIO.OUT)
        GPIO.setup(ena,GPIO.OUT)

        GPIO.setup(inb1,GPIO.OUT)
        GPIO.setup(inb2,GPIO.OUT)
        GPIO.setup(enb,GPIO.OUT)
        
        p1.start(0)
        p2.start(0)
        p1.ChangeDutyCycle(0)
        p2.ChangeDutyCycle(0)
        pa.start(25)
        pb.start(25)
        
    def cleanUp(self):
        global p1
        global p2
        p1.stop()
        p2.stop()
        print(" GPIO.cleanUp() ")
        GPIO.cleanup()
        sleep(2)
    
    def initMotorPosition(self):
        # Init
        global p1
        global p2
        p1.ChangeDutyCycle(cameraPositionX)
        p2.ChangeDutyCycle(cameraPositionY)
        sleep(0.1)
        p1.ChangeDutyCycle(0)
        p2.ChangeDutyCycle(0)
        print("> Init Vert=" + str(cameraPositionX) + ",Hort=" + str(cameraPositionY))
        return "Vert=" + str(cameraPositionX) + ",Hort=" + str(cameraPositionY)

    def moveUp(self):
        global verticalVal
        global horizontalVal
        global p2
        if(verticalVal<12):
            verticalVal = round(verticalVal+0.2, 1)
            p2.ChangeDutyCycle(verticalVal)
            print("> UP Vert=" + str(verticalVal) + ",Hort=" + str(horizontalVal))
            sleep(0.1)
            p2.ChangeDutyCycle(0)
        return "Vert=" + str(verticalVal) + ",Hort=" + str(horizontalVal)
        
    def moveDown(self):
        global verticalVal
        global horizontalVal
        global p2
        if(verticalVal>5):
            verticalVal = round(verticalVal-0.2, 1)
            p2.ChangeDutyCycle(verticalVal)
            print("> Down Vert=" + str(verticalVal) + ",Hort=" + str(horizontalVal))
            sleep(0.1)
            p2.ChangeDutyCycle(0)
        return "Vert=" + str(verticalVal) + ",Hort=" + str(horizontalVal)
        
    def moveRight(self):
        global verticalVal
        global horizontalVal
        global p1
        if(horizontalVal>2.5):
            horizontalVal = round(horizontalVal-0.2, 1)
            p1.ChangeDutyCycle(horizontalVal)
            print("> Right Vert=" + str(verticalVal) + ",Hort=" + str(horizontalVal))
            sleep(0.1)
            p1.ChangeDutyCycle(0)
        return "Vert=" + str(verticalVal) + ",Hort=" + str(horizontalVal)
        
    def moveLeft(self):
        global verticalVal
        global horizontalVal
        global p1
        if(horizontalVal<10):
            horizontalVal = round(horizontalVal+0.2, 1)
            p1.ChangeDutyCycle(horizontalVal)
            print("> Left Vert=" + str(verticalVal) + ",Hort=" + str(horizontalVal))
            sleep(0.1)
            p1.ChangeDutyCycle(0)
        return "Vert=" + str(verticalVal) + ",Hort=" + str(horizontalVal)

        
    def goForward(self,time):
        print("Go forward")
        pa.ChangeDutyCycle(75)
        GPIO.output(ina1,GPIO.HIGH)
        GPIO.output(ina2,GPIO.LOW)
        pb.ChangeDutyCycle(75)
        GPIO.output(inb1,GPIO.HIGH)
        GPIO.output(inb2,GPIO.LOW)
        sleep(0.1*int(time))
        GPIO.output(ina1,GPIO.LOW)
        GPIO.output(ina2,GPIO.LOW)
        GPIO.output(inb1,GPIO.LOW)
        GPIO.output(inb2,GPIO.LOW)
        return " >> Go Forward"

    def goBackward(self,time):
        print("Go backward")
        pa.ChangeDutyCycle(75)
        GPIO.output(ina1,GPIO.LOW)
        GPIO.output(ina2,GPIO.HIGH)
        pb.ChangeDutyCycle(75)
        GPIO.output(inb1,GPIO.LOW)
        GPIO.output(inb2,GPIO.HIGH)
        sleep(0.1*int(time))
        GPIO.output(ina1,GPIO.LOW)
        GPIO.output(ina2,GPIO.LOW)
        GPIO.output(inb1,GPIO.LOW)
        GPIO.output(inb2,GPIO.LOW)
        return " >> Go Backward"

    def goTurnleftback(self,time):
        print("Go Turn Left back")
        pa.ChangeDutyCycle(75)
        GPIO.output(inb1,GPIO.LOW)
        GPIO.output(inb2,GPIO.HIGH)
        sleep(0.1*int(time))
        GPIO.output(ina1,GPIO.LOW)
        GPIO.output(ina2,GPIO.LOW)
        GPIO.output(inb1,GPIO.LOW)
        GPIO.output(inb2,GPIO.LOW)
        return " >> Go Turn Left back"

    def goTurnrightback(self,time):
        print("Go Turn Right back")
        pb.ChangeDutyCycle(75)
        GPIO.output(ina1,GPIO.LOW)
        GPIO.output(ina2,GPIO.HIGH)
        sleep(0.1*int(time))
        GPIO.output(ina1,GPIO.LOW)
        GPIO.output(ina2,GPIO.LOW)
        GPIO.output(inb1,GPIO.LOW)
        GPIO.output(inb2,GPIO.LOW)
        return " >> Go Turn Right back"

    def goTurnleftforward(self,time):
        print("Go Turn Left forward")
        pa.ChangeDutyCycle(75)
        GPIO.output(inb1,GPIO.HIGH)
        GPIO.output(inb2,GPIO.LOW)
        sleep(0.1*int(time))
        GPIO.output(ina1,GPIO.LOW)
        GPIO.output(ina2,GPIO.LOW)
        GPIO.output(inb1,GPIO.LOW)
        GPIO.output(inb2,GPIO.LOW)
        return " >> Go Turn Left forward"

    def goTurnrightforward(self,time):
        print("Go Turn Right forward")
        pb.ChangeDutyCycle(75)
        GPIO.output(ina1,GPIO.HIGH)
        GPIO.output(ina2,GPIO.LOW)
        sleep(0.1*int(time))
        GPIO.output(ina1,GPIO.LOW)
        GPIO.output(ina2,GPIO.LOW)
        GPIO.output(inb1,GPIO.LOW)
        GPIO.output(inb2,GPIO.LOW)
        return " >> Go Turn Right forward"




    def move_to_position(self,ObjX, ObjY):
        global cameraPositionX
        global cameraPositionY
        global p1
        global p2
        print(" >> Move to location x="+str(ObjX)+", y="+str(ObjY))
        moveLoop = True
        movX = int(IM_WIDTH/2)-ObjX
        movY = int(IM_HEIGHT/2)-ObjY
        print(" >> Center location movX="+str(movX)+", movY="+str(movY))
        
        xx = 1
        xy = 0
        yx = 1
        yy = 0
        while(moveLoop):
            if( xy < abs(movX) ):
                p1.ChangeDutyCycle(cameraPositionX)
                sleep(0.1)
                p1.ChangeDutyCycle(0)
                print("xx=" + str(xx) + ", xy="+ str(xy) +" cameraPositionX=" +str(round(cameraPositionX,1)))
                xy = xx*xx * 12
                xx = xx + 1
                if(movX > 0): cameraPositionX = cameraPositionX - 0.2
                else: cameraPositionX = cameraPositionX + 0.2
            if( yy < abs(movY) ):
                p2.ChangeDutyCycle(cameraPositionY)
                sleep(0.1)
                p2.ChangeDutyCycle(0)
                print("yx=" + str(yx) + ", yy="+ str(yy) +" cameraPositionY=" +str(round(cameraPositionY,1)))
                yy = yx*yx * 12
                yx = yx + 1
                if(movY > 0): cameraPositionY = cameraPositionY + 0.2
                else: cameraPositionY = cameraPositionY - 0.2
            elif( xy >= movX and yy >= movY):
                print(" >> Center location movX="+str(movX)+", movY=" + str(movY))
                print(" >> Position location xy="+str(xy)
                      +", yy="+str(yy)
                      +" cameraPositionX="+str(round(cameraPositionX,1))+
                       " cameraPositionY="+str(round(cameraPositionY,1))+" .. ")
                moveLoop = False
        
    def shooting(self):
        GPIO.setup(fire,GPIO.OUT)
        GPIO.output(fire,GPIO.HIGH)
        sleep(0.5)
        GPIO.output(fire,GPIO.LOW)
        GPIO.cleanup()
        self.startUp()
        return "Fired !"  
 

 

듣기와 번역하여 말하기 프로그램 [listenSpeech.py]

listenSpeech.py

의외로 간단 ㅎㅎ 구글님의 지원을 받아서 

from google_trans_new import google_translator  
from google_speech import Speech
from time import sleep

translator = google_translator()

class ListenSpeech(object):
    def speech(self,message):
        ko_result = translator.translate(message, lang_tgt='ko')
        print(' -> ', ko_result)
        speech = Speech(ko_result, 'ko')
        speech.play()
        en_result = translator.translate(message, lang_tgt='en')
        speech = Speech(en_result, 'en')
        speech.play()
        it_result = translator.translate(message, lang_tgt='it')
        speech = Speech(it_result, 'it')
        speech.play()
        ja_result = translator.translate(message, lang_tgt='ja')
        speech = Speech(ja_result, 'ja')
        speech.play()
        cn_result = translator.translate(message, lang_tgt='cmn')
        speech = Speech(cn_result, 'cmn')
        speech.play()
        returnString = ko_result + " , EN=" + en_result + " , IT=" + it_result + ", JA=" + ja_result + " , CMN=" + cn_result
        print("Return message = " + returnString)
        return returnString
        

 

화면 캡쳐 [capture.py]

capture.py

 

import cv2
import datetime, time
from pathlib import Path

def capture_and_save(im):
    s = im.shape
    # Add a timestamp
    font = cv2.FONT_HERSHEY_SIMPLEX
    bottomLeftCornerOfText = (10,s[0]-10)
    fontScale = 1
    fontColor = (20,20,20)
    lineType = 2

    cv2.putText(im,datetime.datetime.now().isoformat().split(".")[0],bottomLeftCornerOfText,font,fontScale,fontColor, lineType)

    m = 0
    p = Path("archive")
    for imp in p.iterdir():
        if imp.suffix == ".png" and imp.stem != "last":
            num = imp.stem.split("_")[1]
            try:
                num = int(num)
                if num>m:
                    m = num
            except:
                print("Error reading image number for",str(imp))
    m +=1
    lp = Path("archive/last.png")
    if lp.exists() and lp.is_file():
        np = Path("archive/img_{}.png".format(m))
        np.write_bytes(lp.read_bytes())
    cv2.imwrite("archive/last.png",im)

if __name__=="__main__":
    capture_and_save()
    print("done")

 

기타 프로그램 및 화면 소스

기타 프로그램 및 화면 소스

conf.py


from pathlib import Path

p = Path("logs")
if not p.exists():
    p.mkdir()

dictConfig = {
    'version': 1,
    'disable_existing_loggers': True,
    'formatters': {
        'standard': {
            'format': '%(asctime)s [%(levelname)s] %(name)s:: %(message)s',
        },
    },
    'handlers': {
        'default': {
            'level': 'DEBUG',
            'formatter': 'standard',
            'class': 'logging.StreamHandler',
            'stream': 'ext://sys.stdout',
        },
        'file': {
            'class': 'logging.handlers.RotatingFileHandler',
            'level': 'DEBUG',
            'formatter': 'standard',
            'filename': 'logs/logfile.log',
            'mode': 'a',
            'maxBytes': 5_242_880,
            'backupCount': 3,
            'encoding': 'utf-8',
        },
    },
    'loggers': {
        '__main__': {
            'handlers': ['default','file'],
            'level': 'DEBUG',
            'propagate': False,
        },
        'camera': {
            'handlers': ['default', 'file'],
            'level': 'DEBUG',
            'propagate': False,
        },
    }
}

폴더구조 

/home/hyunsu/work .... 

image.png

화면 소스 

templates.zip

 

공통 화면 라이브러리 

static.zip