Integration of raspimjpeg

The source code of the modified version of raspimjpeg used by the PlanktoScope is hosted [here](https://github.com/PlanktonPlanet/userland/tree/master/host_applications/linux/apps/raspicam).

We moved away from picamera to improve the stability of the system. This commit should closes the elusive #51 and #54.

After a lot of tests, it was clear that even a forked version of picamera was not going to solve our problem while also improving on our capturing speed.

The modified version of RaspiMJPEG does that.
RaspiMJPEG streams the image flux to /dev/shm/mjpeg/cam.jpg . This is passively reloaded by the streaming server (still written in python).

RaspiMJPEG is controlled through a special file called a Pipe which is used to send it commands.
The list is available [here](https://github.com/PlanktonPlanet/userland/tree/master/host_applications/linux/apps/raspicam/Config.md).

The raspimjpeg binary is distributed directly in this repository, in the folder `scripts/raspimjpeg/bin/`.
This commit is contained in:
Romain Bazile 2020-11-16 17:39:45 +01:00
parent fcb57ed075
commit f27c9823a1
10 changed files with 980 additions and 281 deletions

View file

@ -173,35 +173,6 @@ The device appearing at addresses 60 and 70 is our motor controller. Address `0d
In case the motor controller does not appear, shutdown your Planktoscope and check the wiring. If your board is using a connector instead of a soldered pin connection (as happens with the Adafruit Bonnet Motor Controller), sometimes the pins on the male side need to be bent a little to make good contact. In any case, do not hesitate to ask for help in Slack.
### Install RPi Cam Web Interface
You can find more information about the RPi Cam Web Interface on [eLinux' website](https://elinux.org/RPi-Cam-Web-Interface).
To set it up, clone the code from Github and enable and run the install script with the following commands
```sh
cd ~/libraries
git clone https://github.com/silvanmelchior/RPi_Cam_Web_Interface.git
cd RPi_Cam_Web_Interface
./install.sh
```
Change the autostart setting to No, and then press Enter to allow default setting of the installation. Once everything is installed, press Enter to start the RPi Cam Web Interface now.
To test the interface locally, try accessing this url from the browser in the Raspberry: http://localhost/html
You can also try to access this page from another computer connected to the same network.
If your computer has `avahi` or the `Bonjour` service installed and running, you can directly use this url: http://raspberrypi.local/html/ .
If this is not the case, you first need to find the IP address of your Raspberry Pi by running the following:
```sh
sudo ip addr show | grep 'inet 1'
```
The web page can then be accessed at `http://[IP_ADDRESS]/html/`.
If the interface is loading and a picture is displayed, you can now stop this interface for now by simply running `./stop.sh`.
### Install Ultimate GPS HAT

View file

@ -5,5 +5,6 @@
"pump_steps_per_ml": 507,
"focus_max_speed": 0.5,
"pump_max_speed": 30,
"stepper_type" : "adafruit"
"stepper_type": "adafruit",
"camera_type": "HQ"
}

View file

@ -12,10 +12,10 @@ import datetime
import time
# Libraries manipulate json format, execute bash commands
import json, shutil, os
import json, shutil
# Library to control the PiCamera
import picamera
# Library for path and filesystem manipulations
import os
# Library for starting processes
import multiprocessing
@ -27,36 +27,22 @@ import planktoscope.light
# import planktoscope.streamer
import planktoscope.imager_state_machine
# import raspimjpeg module
import planktoscope.raspimjpeg
################################################################################
# Streaming PiCamera over server
################################################################################
import io
import socketserver
import http.server
import threading
import functools
################################################################################
# Classes for the PiCamera Streaming
################################################################################
class StreamingOutput(object):
def __init__(self):
self.frame = None
self.buffer = io.BytesIO()
self.condition = threading.Condition()
def write(self, buf):
if buf.startswith(b"\xff\xd8"):
# New frame, copy the existing buffer's content and notify all
# clients it's available
self.buffer.truncate()
with self.condition:
self.frame = self.buffer.getvalue()
self.condition.notify_all()
self.buffer.seek(0)
return self.buffer.write(buf)
class StreamingHandler(http.server.BaseHTTPRequestHandler):
# Webpage content containing the PiCamera Streaming
PAGE = """\
@ -70,6 +56,10 @@ class StreamingHandler(http.server.BaseHTTPRequestHandler):
</html>
"""
def __init__(self, delay, *args, **kwargs):
self.delay = delay
super(StreamingHandler, self).__init__(*args, **kwargs)
@logger.catch
def do_GET(self):
if self.path == "/":
@ -95,15 +85,23 @@ class StreamingHandler(http.server.BaseHTTPRequestHandler):
self.end_headers()
try:
while True:
with output.condition:
output.condition.wait()
frame = output.frame
try:
with open("/dev/shm/mjpeg/cam.jpg", "rb") as jpeg:
frame = jpeg.read()
except FileNotFoundError as e:
logger.error(f"Camera has not been started yet")
time.sleep(5)
except Exception as e:
logger.exception(f"An exception occured {e}")
else:
self.wfile.write(b"--FRAME\r\n")
self.send_header("Content-Type", "image/jpeg")
self.send_header("Content-Length", len(frame))
self.end_headers()
self.wfile.write(frame)
self.wfile.write(b"\r\n")
time.sleep(self.delay)
except BrokenPipeError as e:
logger.info(f"Removed streaming client {self.client_address}")
else:
@ -116,11 +114,8 @@ class StreamingServer(socketserver.ThreadingMixIn, http.server.HTTPServer):
daemon_threads = True
output = StreamingOutput()
logger.info("planktoscope.imager is loaded")
################################################################################
# Main Imager class
################################################################################
@ -128,20 +123,35 @@ class ImagerProcess(multiprocessing.Process):
"""This class contains the main definitions for the imager of the PlanktoScope"""
@logger.catch
def __init__(self, event, resolution=(3280, 2464), iso=60, shutter_speed=500):
def __init__(self, stop_event, iso=100, shutter_speed=500):
"""Initialize the Imager class
Args:
event (multiprocessing.Event): shutdown event
resolution (tuple, optional): Camera native resolution. Defaults to (3280, 2464).
iso (int, optional): ISO sensitivity. Defaults to 60.
stop_event (multiprocessing.Event): shutdown event
iso (int, optional): ISO sensitivity. Defaults to 100.
shutter_speed (int, optional): Shutter speed of the camera. Defaults to 500.
"""
super(ImagerProcess, self).__init__(name="imager")
logger.info("planktoscope.imager is initialising")
self.stop_event = event
if os.path.exists("/home/pi/PlanktonScope/hardware.json"):
# load hardware.json
with open("/home/pi/PlanktonScope/hardware.json", "r") as config_file:
configuration = json.load(config_file)
logger.debug(f"Hardware configuration loaded is {configuration}")
else:
logger.info(
"The hardware configuration file doesn't exists, using defaults"
)
configuration = {}
self.__camera_type = "v2.1"
# parse the config data. If the key is absent, we are using the default value
self.__camera_type = configuration.get("camera_type", self.__camera_type)
self.stop_event = stop_event
self.__imager = planktoscope.imager_state_machine.Imager()
self.__img_goal = 0
self.__img_done = 0
@ -149,8 +159,29 @@ class ImagerProcess(multiprocessing.Process):
self.__pump_volume = None
self.__img_goal = None
self.imager_client = None
self.__camera = None
self.__resolution = resolution
# Initialise the camera and the process
# Also starts the streaming to the temporary file
self.__camera = planktoscope.raspimjpeg.raspimjpeg()
try:
self.__camera.start()
except Exception as e:
logger.exception(
f"An exception has occured when starting up raspimjpeg: {e}"
)
exit(1)
if self.__camera.sensor_name == "IMX219": # Camera v2.1
self.__resolution = (3280, 2464)
elif self.__camera.sensor_name == "IMX477": # Camera HQ
self.__resolution = (4056, 3040)
else:
self.__resolution = (1280, 1024)
logger.error(
f"The connected camera {self.__camera.sensor_name} is not recognized, please check your camera"
)
self.__iso = iso
self.__shutter_speed = shutter_speed
self.__exposure_mode = "fixedfps"
@ -158,12 +189,43 @@ class ImagerProcess(multiprocessing.Process):
self.__export_path = ""
self.__global_metadata = None
logger.success("planktoscope.imager is initialised and ready to go!")
logger.info("Initialising the camera with the default settings")
try:
self.__camera.resolution = self.__resolution
except TimeoutError as e:
logger.error(
"A timeout has occured when setting the resolution, trying again"
)
self.__camera.resolution = self.__resolution
time.sleep(0.1)
@logger.catch
def start_camera(self):
"""Start the camera streaming process"""
self.__camera.start_recording(output, format="mjpeg", resize=(640, 480))
try:
self.__camera.iso = self.__iso
except TimeoutError as e:
logger.error(
"A timeout has occured when setting the ISO number, trying again"
)
self.__camera.iso = self.__iso
time.sleep(0.1)
try:
self.__camera.shutter_speed = self.__shutter_speed
except TimeoutError as e:
logger.error(
"A timeout has occured when setting the shutter speed, trying again"
)
self.__camera.shutter_speed = self.__shutter_speed
time.sleep(0.1)
try:
self.__camera.exposure_mode = self.__exposure_mode
except TimeoutError as e:
logger.error(
"A timeout has occured when setting the exposure mode, trying again"
)
self.__camera.exposure_mode = self.__exposure_mode
logger.success("planktoscope.imager is initialised and ready to go!")
def pump_callback(self, client, userdata, msg):
"""Callback for when we receive an MQTT message
@ -444,7 +506,10 @@ class ImagerProcess(multiprocessing.Process):
)
# Capture an image with the proper filename
try:
self.__camera.capture(filename_path)
except TimeoutError as e:
logger.error("A timeout happened while waiting for a capture to happen")
# Set the LEDs as Green
planktoscope.light.setRGB(0, 255, 0)
@ -529,19 +594,12 @@ class ImagerProcess(multiprocessing.Process):
self.imager_client.client.publish("status/imager", '{"status":"Starting up"}')
logger.info("Initialising the camera")
# PiCamera settings
self.__camera = picamera.PiCamera(resolution=self.__resolution)
# TODO Check camera version here
self.__camera.iso = self.__iso
self.__camera.shutter_speed = self.__shutter_speed
self.__camera.exposure_mode = self.__exposure_mode
address = ("", 8000)
server = StreamingServer(address, StreamingHandler)
# Starts the streaming server process
logger.info("Starting the streaming server thread")
self.start_camera()
address = ("", 8000)
fps = 16
refresh_delay = 1 / fps
handler = functools.partial(StreamingHandler, refresh_delay)
server = StreamingServer(address, handler)
self.streaming_thread = threading.Thread(
target=server.serve_forever, daemon=True
)
@ -552,16 +610,14 @@ class ImagerProcess(multiprocessing.Process):
logger.success("Camera is READY!")
# This is the loop
# This is the main loop
while not self.stop_event.is_set():
self.treat_message()
self.state_machine()
time.sleep(0.001)
logger.info("Shutting down the imager process")
self.imager_client.client.publish("status/imager", '{"status":"Dead"}')
logger.debug("Stopping the camera")
self.__camera.stop_recording()
logger.debug("Stopping the raspimjpeg process")
self.__camera.close()
logger.debug("Stopping the streaming thread")
server.shutdown()

View file

@ -0,0 +1,447 @@
################################################################################
# Practical Libraries
################################################################################
# Logger library compatible with multiprocessing
from loguru import logger
# Library for path and filesystem manipulations
import os
# Library to get date and time for folder name and filename
import datetime
import time
# Library to control the RaspiMJPEG process
import subprocess # nosec
################################################################################
# Class for the communication with RaspiMJPEG
################################################################################
class raspimjpeg(object):
def __init__(self, *args, **kwargs):
self.__configfile = "/home/pi/PlanktonScope/scripts/raspimjpeg/raspimjpeg.conf"
self.__binary = "/home/pi/PlanktonScope/scripts/raspimjpeg/bin/raspimjpeg"
self.__statusfile = "/dev/shm/mjpeg/status_mjpeg.txt"
self.__pipe = "/home/pi/PlanktonScope/scripts/raspimjpeg/FIFO"
# make sure the status file exists and is empty
if not os.path.exists(self.__statusfile):
logger.debug("The status file does not exists, creating now")
# create the path!
os.makedirs(os.path.dirname(self.__statusfile), exist_ok=True)
# If the file does not exists, creates it
# otherwise make sure it's empty
with open(self.__statusfile, "w") as file:
file.write("")
# make sure the pipe exists
if not os.path.exists(self.__pipe):
logger.debug("The pipe does not exists, creating now")
os.makedirs(os.path.dirname(self.__pipe), exist_ok=True)
os.mkfifo(self.__pipe)
# make sure the config file exists
if not os.path.exists(self.__configfile):
logger.error("The config file does not exists!")
def start(self):
logger.debug("Starting up raspimjpeg")
# The input to this call are perfectly controlled
# hence the nosec comment to deactivate bandit error
self.__process = subprocess.Popen( # nosec
[self.__binary, "-c", self.__configfile],
stdout=subprocess.PIPE,
bufsize=1, # means line buffered
text=True,
)
# self.__process.stdout can be read as a file
# This will set the reads on stdout to be non-blocking
os.set_blocking(self.__process.stdout.fileno(), False)
try:
name_string = self.__parse_output_for("Camera Name")
self.__sensor_name = name_string.rsplit(" ", 1)[1].upper().rstrip()
except TimeoutError as e:
logger.exception(
f"A timeout happened while waiting for RaspiMJPEG to start: {e}"
)
try:
width_string = self.__parse_output_for("Camera Max Width:")
self.__width = width_string.rsplit(" ", 1)[1]
except TimeoutError as e:
logger.exception(
f"A timeout happened while waiting for RaspiMJPEG to start: {e}"
)
try:
height_string = self.__parse_output_for("Camera Max Height")
self.__height = height_string.rsplit(" ", 1)[1]
except TimeoutError as e:
logger.exception(
f"A timeout happened while waiting for RaspiMJPEG to start: {e}"
)
try:
self.__wait_for_output("Starting command loop")
except TimeoutError as e:
logger.exception(
f"A timeout happened while waiting for RaspiMJPEG to start: {e}"
)
def status(self):
return self.__get_status()
def __parse_output_for(self, text, timeout=5):
"""Blocking, waiting for specific output from process
Continously poll the process stdout file object.
Args:
text (string): String to wait for
timeout (int, optional): Timeout duration in seconds. Defaults to 5.
Raises:
TimeoutError: A timeout happened before the required output showed up
"""
logger.debug(f"Parsing the output for {text} for {timeout}s")
wait_until = datetime.datetime.now() + datetime.timedelta(seconds=timeout)
break_loop = False
while True:
for nextline in self.__process.stdout:
logger.trace(f"last read line is {nextline}")
if nextline.startswith(text):
return nextline
if wait_until < datetime.datetime.now():
# The timeout has been reached!
logger.error("A timeout has occured waiting for a RaspiMJPEG answer")
raise TimeoutError
time.sleep(0.1)
def __wait_for_output(self, output, timeout=5):
"""Blocking, waiting for specific output from process
Continously poll the process stdout file object.
Args:
output (string): String to wait for
timeout (int, optional): Timeout duration in seconds. Defaults to 5.
Raises:
TimeoutError: A timeout happened before the required output showed up
"""
logger.debug(f"Waiting for {output} for {timeout}s")
wait_until = datetime.datetime.now() + datetime.timedelta(seconds=timeout)
break_loop = False
while True:
for nextline in self.__process.stdout:
logger.trace(f"last read line is {nextline}")
if nextline.startswith("Error:"):
logger.error(f"RaspiMJPEG error: {nextline}")
elif nextline.startswith(output):
return
if wait_until < datetime.datetime.now():
# The timeout has been reached!
logger.error("A timeout has occured waiting for a RaspiMJPEG answer")
raise TimeoutError
time.sleep(0.1)
def __get_status(self):
"""Open and return the status file content
Returns:
string: status of the process
"""
logger.trace("Getting the status file")
try:
with open(self.__statusfile, "r") as status:
status = status.read()
logger.trace(f"Read {status} from {self.__statusfile}")
return status
except FileNotFoundError as e:
logger.error(
f"The status file was not found, make sure the filesystem has not been corrupted"
)
return ""
def __wait_for_status(self, status, timeout=5):
"""Wait for a specific status. Blocking, obviously.
Args:
status (string): The status to wait for
"""
logger.debug(f"Waiting for {status} for {timeout}s")
wait_until = datetime.datetime.now() + datetime.timedelta(seconds=timeout)
message = self.__get_status()
while True:
if message.startswith(status):
return
if wait_until < datetime.datetime.now():
# The timeout has been reached!
logger.error("A timeout has occured waiting for a RaspiMJPEG answer")
raise TimeoutError
time.sleep(0.1)
logger.debug(f"not {status} yet")
message = self.__get_status()
def __send_command(self, command):
"""Sends a command to the RaspiMJPEG process
Args:
command (string): the command string to send
"""
# TODO add check to make sure the pipe is open on the other side, otherwise this is blocking.
# Maybe just check that self.__process is still alive? :-)
logger.debug(f"Sending the command [{command}] to raspimjpeg")
with open(self.__pipe, "w") as pipe:
pipe.write(f"{command}\n")
@property
def sensor_name(self):
"""Sensor name of the connected camera
Returns:
string: Sensor name. One of OV5647 (cam v1), IMX219 (cam v2.1), IMX477(ca HQ)
"""
return self.__sensor_name
@property
def width(self):
return self.__width
@property
def height(self):
return self.__height
@property
def resolution(self):
return self.__resolution
@resolution.setter
def resolution(self, resolution):
"""Change the camera image resolution
For a full FOV, allowable resolutions are:
- (3280,2464), (1640,1232), (1640,922) for Camera V2.1
- (2028,1520), (4056,3040) for HQ Camera
Args:
resolution (tuple of int): resolution to set the camera to
"""
logger.debug(f"Setting the resolution to {resolution}")
if resolution in [
(3280, 2464),
(1640, 1232),
(1640, 922),
(2028, 1520),
(4056, 3040),
]:
self.__resolution = resolution
self.__send_command(
f"px 1640 1232 15 15 {self.__resolution[0]} {self.__resolution[1]} 01"
)
else:
logger.error(f"The resolution specified ({resolution}) is not valid")
raise ValueError
@property
def iso(self):
return self.__iso
@iso.setter
def iso(self, iso):
"""Change the camera iso number
Iso number will be rounded to the closest one of
0, 100, 200, 320, 400, 500, 640, 800.
If 0, Iso number will be chosen automatically by the camera
Args:
iso (int): Iso number
"""
logger.debug(f"Setting the iso number to {iso}")
if 0 <= iso <= 800:
self.__iso = iso
self.__send_command(f"is {self.__iso}")
self.__wait_for_output("Change: iso")
else:
logger.error(f"The ISO number specified ({iso}) is not valid")
raise ValueError
@property
def shutter_speed(self):
return self.__shutter_speed
@shutter_speed.setter
def shutter_speed(self, shutter_speed):
"""Change the camera shutter speed
Args:
shutter_speed (int): shutter speed in µs
"""
logger.debug(f"Setting the shutter speed to {shutter_speed}")
if 0 < shutter_speed < 5000:
self.__shutter_speed = shutter_speed
self.__send_command(f"ss {self.__shutter_speed}")
self.__wait_for_output("Change: shutter_speed")
else:
logger.error(f"The shutter speed specified ({shutter_speed}) is not valid")
raise ValueError
@property
def exposure_mode(self):
return self.__exposure_mode
@exposure_mode.setter
def exposure_mode(self, mode):
"""Change the camera exposure mode
Is one of off, auto, night, nightpreview, backlight, spotlight,
sports, snow, beach, verylong, fixedfps, antishake, fireworks
Args:
mode (string): exposure mode to use
"""
logger.debug(f"Setting the exposure mode to {mode}")
if mode in [
"off",
"auto",
"night",
"nightpreview",
"backlight",
"spotlight",
"sports",
"snow",
"beach",
"verylong",
"fixedfps",
"antishake",
"fireworks",
]:
self.__exposure_mode = mode
self.__send_command(f"em {self.__exposure_mode}")
else:
logger.error(f"The exposure mode specified ({mode}) is not valid")
raise ValueError
@property
def white_balance(self):
return self.__white_balance
@white_balance.setter
def white_balance(self, mode):
"""Change the camera white balance mode
Is one of off, auto, sun, cloudy, shade, tungsten,
fluorescent, incandescent, flash, horizon
Args:
mode (string): white balance mode to use
"""
logger.debug(f"Setting the white balance mode to {mode}")
if mode in [
"off",
"auto",
"sun",
"cloudy",
"shade",
"tungsten",
"fluorescent",
"incandescent",
"flash",
"horizon",
]:
self.__white_balance = mode
self.__send_command(f"wb {self.__white_balance}")
else:
logger.error(
f"The camera white balance mode specified ({mode}) is not valid"
)
raise ValueError
@property
def image_quality(self):
return self.__image_quality
@image_quality.setter
def image_quality(self, image_quality):
"""Change the output image quality
Args:
image_quality (int): image quality [0,100]
"""
logger.debug(f"Setting image quality to {image_quality}")
if 0 <= image_quality <= 100:
self.__image_quality = image_quality
self.__send_command(f"ss {self.__image_quality}")
else:
logger.error(
f"The output image quality specified ({image_quality}) is not valid"
)
raise ValueError
@property
def preview_quality(self):
return self.__preview_quality
@preview_quality.setter
def preview_quality(self, preview_quality):
"""Change the preview image quality
Args:
preview_quality (int): image quality [0,100]
"""
logger.debug(f"Setting preview quality to {preview_quality}")
if 0 <= preview_quality <= 100:
self.__preview_quality = preview_quality
self.__send_command(f"pv {self.__preview_quality} 512 01")
else:
logger.error(
f"The preview image quality specified ({preview_quality}) is not valid"
)
raise ValueError
def capture(self, path="", timeout=5):
"""Capture an image. Blocks for timeout seconds(5 by default) until the image is captured.
Args:
path (str, optional): Path to image file. Defaults to "".
timeout (int, optional): Timeout duration in seconds. Defaults to 5.
Raises:
TimeoutError: A timeout happened before the required output showed up
"""
logger.debug(f"Capturing an image to {path}")
if path == "":
self.__send_command(f"im")
else:
self.__send_command(f"im {path}")
self.__wait_for_output("Capturing image", timeout / 2)
self.__wait_for_status("ready", timeout / 2)
def stop(self):
"""Halt and release the camera. """
logger.debug("Releasing the camera now")
self.__send_command(f"ru 0")
def close(self):
"""Kill the process."""
logger.debug("Killing raspimjpeg in a nice way")
self.__process.terminate()
self.__process.wait()

BIN
scripts/raspimjpeg/bin/raspimjpeg Executable file

Binary file not shown.

BIN
scripts/raspimjpeg/bin/raspistill Executable file

Binary file not shown.

View file

@ -0,0 +1,2 @@
#!/bin/bash
sudo shutdown -r now

View file

@ -0,0 +1,40 @@
#!/bin/bash
# example start up script which converts any existing .h264 files into MP4
MACRODIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )"
BASEDIR="$( cd "$( dirname "${MACRODIR}" )" >/dev/null 2>&1 && pwd )"
mypidfile=${MACRODIR}/startstop.sh.pid
mylogfile=${BASEDIR}/scheduleLog.txt
#Check if script already running
NOW=`date +"-%Y/%m/%d %H:%M:%S-"`
if [ -f $mypidfile ]; then
echo "${NOW} Script already running..." >> ${mylogfile}
exit
fi
#Remove PID file when exiting
trap "rm -f -- '$mypidfile'" EXIT
echo $$ > "$mypidfile"
#Do conversion
if [ "$1" == "start" ]; then
cd ${MACRODIR}
cd ../media
shopt -s nullglob
for f in *.h264
do
f1=${f%.*}.mp4
NOW=`date +"-%Y/%m/%d %H:%M:%S-"`
echo "${NOW} Converting $f" >> ${mylogfile}
#set -e;MP4Box -fps 25 -add $f $f1 > /dev/null 2>&1;rm $f;
if MP4Box -fps 25 -add $f $f1; then
NOW=`date +"-%Y/%m/%d %H:%M:%S-"`
echo "${NOW} Conversion complete, removing $f" >> ${mylogfile}
rm $f
else
NOW=`date +"-%Y/%m/%d %H:%M:%S-"`
echo "${NOW} Error with $f" >> ${mylogfile}
fi
done
fi

View file

@ -0,0 +1,2 @@
#!/bin/bash
date >/var/www/testmacro.txt

View file

@ -0,0 +1,180 @@
################################
# Config File for raspimjpeg #
################################
# Syntax: "Command Param", no spaces before/after line allowed
#
# Camera Options
#
# annotation max length: 31 characters
annotation
anno_background false
anno3_custom_background_colour 0
anno3_custom_background_Y 0
anno3_custom_background_U 128
anno3_custom_background_V 128
anno3_custom_text_colour 0
anno3_custom_text_Y 255
anno3_custom_text_U 128
anno3_custom_text_V 128
anno_text_size 50
sharpness 0
contrast 0
brightness 50
saturation 0
iso 0
metering_mode average
video_stabilisation false
exposure_compensation 0
exposure_mode auto
white_balance auto
autowbgain_r 150
autowbgain_b 150
image_effect none
colour_effect_en false
colour_effect_u 128
colour_effect_v 128
rotation 0
hflip false
vflip false
sensor_region_x 0
sensor_region_y 0
sensor_region_w 65536
sensor_region_h 65536
shutter_speed 0
raw_layer false
stat_pass 0
# camera_num 0 - no selection. 1/2 selects first or second camera on compute module
camera_num 0
#MMAL settings
minimise_frag 0
initial_quant 25
encode_qp 31
#mmal_logfile used for debugging callbacks (set to /dev/shm/mjpeg/mmallogfile for short periods only)
mmal_logfile
#sleep after stopping uSec
stop_pause 100000
#
# Preview Options
#
# fps_preview = video_fps (below) / divider
#
width 800
quality 10
divider 1
#
# Video Options
#
video_width 1640
video_height 1232
video_fps 15
video_bitrate 17000000
video_buffer 0
#h264_buffer_size 0 sets to default (65536) Higher gives smoother set of callbacks
h264_buffer_size 131072
h264_buffers 0
video_split 0
#MP4Box Off=leave as raw h264, background=box in background
MP4Box background
MP4Box_fps 25
MP4Box_cmd (set -e;MP4Box -fps %i -add %s %s > /dev/null 2>&1;rm "%s";) &
#
# Image Options
#
image_width 3280
image_height 2464
image_quality 25
#time lapse interval 0.1 sec units
tl_interval 30
#
# Motion Detection
#
motion_external true
vector_preview false
vector_mode ?
motion_noise 1010
motion_threshold 250
motion_clip 0
motion_image
motion_initframes 0
motion_startframes 3
motion_stopframes 150
motion_pipe
motion_file 0
#
# File Locations
#
# preview path: add %d for number
# image+video path: add %d for number, year, month, day, hour, minute, second
# macros_path can be used to store macros executed by sy command
# boxing_path if set is where h264 files will be temporarily stored when boxing used
# image, video and lapse may be configured relative to media_path if first / left out
base_path /home/pi/PlanktonScope/scripts/raspimjpeg/
preview_path /dev/shm/mjpeg/cam.jpg
image_path /home/pi/data/%Y%M%D/im_%i_%h%m%s.jpg
lapse_path /home/pi/media/tl_%i_%t_%Y%M%D_%h%m%s.jpg
video_path /home/pi/media/vi_%v_%Y%M%D_%h%m%s.mp4
status_file /dev/shm/mjpeg/status_mjpeg.txt
control_file /home/pi/PlanktonScope/scripts/raspimjpeg/FIFO
media_path /home/pi/data/
macros_path /home/pi/PlanktonScope/scripts/raspimjpeg/macros
user_annotate /dev/shm/mjpeg/user_annotate.txt
boxing_path
subdir_char @
count_format %04d
#Job macros - prefix with & to make it run asynchronously
error_soft error_soft.sh
error_hard error_hard.sh
start_img start_img.sh
end_img &end_img.sh
start_vid &start_vid.sh
end_vid end_vid.sh
end_box &end_box.sh
do_cmd &do_cmd.sh
motion_event motion_event.sh
startstop startstop.sh
# thumb generator control
# Set v, i, or t in string to enable thumbs for images, videos, or lapse
thumb_gen vt
#
# Autostart
#
# autostart: standard/idle
# motion detection can only be true if autostart is standard
#
autostart standard
motion_detection false
# Watchdog
# Interval in 0.1 secs
# Errors is Number of times cam.jpg doesn't change before exit
watchdog_interval 30
watchdog_errors 3
# Set callback_timeout to 0 to disable it
callback_timeout 30
#optional user_config file to overwrite (persist) changes
user_config /home/pi/PlanktonScope/scripts/raspimjpeg/uconfig
#logfile for raspimjpeg, default to merge with scheduler log
log_file /home/pi/PlanktonScope/scripts/raspimjpeg/raspimjpeg.log
log_size 10000
motion_logfile /home/pi/PlanktonScope/scripts/raspimjpeg/motion.log
#enforce_lf set to 1 to only process FIFO commands when terminated with LF
enforce_lf 1
#FIFO poll interval microseconds 1000000 minimum
fifo_interval 100000