Skip to content

Commit

Permalink
Version 8.6.3
Browse files Browse the repository at this point in the history
  • Loading branch information
s60sc authored Apr 16, 2023
1 parent 1ad0475 commit 10cb064
Show file tree
Hide file tree
Showing 13 changed files with 116 additions and 114 deletions.
3 changes: 1 addition & 2 deletions ESP32-CAM_MJPEG2SD.ino
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
*/

#include "appGlobals.h"
#include "camera_pins.h"

// camera board selected
#if defined(CAMERA_MODEL_AI_THINKER)
Expand Down Expand Up @@ -121,7 +120,7 @@ static void prepCam() {
debugMemory("prepCam");
}

void setup() {
void setup() {
logSetup();
LOG_INF("=============== Starting ===============");
if (!psramFound()) sprintf(startupFailure, "Startup Failure: Need PSRAM to be enabled");
Expand Down
8 changes: 6 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ Changes for version 8.0:
- lamp has variable intensity
- internal code restructuring.

Changes up to version 8.6.1:
Changes up to version 8.6.3:
- Web page improvements and jQuery removed.
- Support for OV5640 and OV3660 cameras, but see [**OV5640**](#ov5640) section below.
- Spurious error [message](https://github.com/s60sc/ESP32-CAM_MJPEG2SD/issues/155) removed.
Expand All @@ -20,6 +20,8 @@ Changes up to version 8.6.1:
- Improve AP stability
- Improve [PIR auto lamp](https://github.com/s60sc/ESP32-CAM_MJPEG2SD/issues/183)
- MQTT integration added by [@gemi254](https://github.com/gemi254), see [**MQTT**](#mqtt) section below.
- Fix for [issue 198](https://github.com/s60sc/ESP32-CAM_MJPEG2SD/issues/198)
- Added deep sleep on night, wake on LDR


## Purpose
Expand Down Expand Up @@ -137,12 +139,14 @@ See [**Motion detection by Camera**](#motion-detection-by-camera) section.
* Connect an external I2S microphone
* Connect a DS18B20 temperature sensor
* Monitor voltage of battery supply on ADC pin
* Wakeup on LDR after deep sleep at night

Note that there are not enough free pins on the ESP32 camera module to allow all external sensors to be used. Pins that can be used (with some limitations) are: 3, 4, 12, 13, 33.
* pin 3: Labelled U0R. Only use as input pin, as also used for flashing.
* pin 4: Also used for onboard lamp. Lamp can be disabled by removing its current limiting resistor.
* pin 12: Only use as output pin.
* pin 33: Used by onboard red LED. Not broken out, but can repurpose the otherwise pointless VCC pin by removing its adjacent resistor marked 3V3, and the red LED current limiting resistor, then running a wire between the VCC pin and the red LED resistor solder tab.
* pin 13: Is weakly pulled high.
* pin 33: Used by onboard red LED. Not broken out, but can repurpose the otherwise pointless VCC pin by removing its adjacent resistor marked 3V3, and the red LED current limiting resistor, then running a wire between the VCC pin and the red LED resistor solder tab.

Can also use the [ESP32-IO_Extender](https://github.com/s60sc/ESP32-IO_Extender) repository.

Expand Down
19 changes: 16 additions & 3 deletions appGlobals.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,10 @@
//#define CAMERA_MODEL_ESP32S2_CAM_BOARD
//#define CAMERA_MODEL_ESP32S3_CAM_LCD

#include "camera_pins.h"

#define ALLOW_SPACES false // set true to allow whitespace in configs.txt key values

// web server ports
#define WEB_PORT 80 // app control
#define STREAM_PORT 81 // camera images
Expand All @@ -47,7 +51,7 @@
#define FLUSH_DELAY 0 // for debugging crashes

#define APP_NAME "ESP-CAM_MJPEG" // max 15 chars
#define APP_VER "8.6.1"
#define APP_VER "8.6.3"

#define MAX_CLIENTS 2 // allowing too many concurrent web clients can cause errors
#define DATA_DIR "/data"
Expand All @@ -65,7 +69,7 @@
#define ONEMEG (1024 * 1024)
#define MAX_PWD_LEN 64
#define JSON_BUFF_LEN (32 * 1024) // set big enough to hold all file names in a folder
#define MAX_CONFIGS 120 // > number of entries in configs.txt
#define MAX_CONFIGS 130 // > number of entries in configs.txt
#define GITHUB_URL "https://raw.githubusercontent.com/s60sc/ESP32-CAM_MJPEG2SD/master"

#define FILE_EXT "avi"
Expand All @@ -85,7 +89,6 @@
#define INCLUDE_FTP
#define INCLUDE_SMTP
#define INCLUDE_SD
#define INCLUDE_MQTT

#define IS_IO_EXTENDER false // must be false unless IO_Extender
#define EXTPIN 100
Expand Down Expand Up @@ -129,6 +132,7 @@ void finishAudio(bool isValid);
mjpegStruct getNextFrame(bool firstCall = false);
bool getPIRval();
bool haveWavFile(bool isTL = false);
bool isNight(uint8_t nightSwitch);
void openSDfile(const char* streamFile);
void prepAviIndex(bool isTL = false);
bool prepRecording();
Expand Down Expand Up @@ -183,6 +187,7 @@ extern float motionVal; // motion sensitivity setting - min percentage of chang
extern uint8_t nightSwitch; // initial white level % for night/day switching
extern bool nightTime;
extern bool stopPlayback;
extern bool isStreaming;
extern bool useMotion; // whether to use camera for motion detection (with motionDetect.cpp)
extern bool timeLapseOn; // enable time lapse recording
extern int maxFrames;
Expand All @@ -209,15 +214,20 @@ extern int uartRxdPin;
extern bool pirUse; // true to use PIR for motion detection
extern bool lampUse; // true to use lamp
extern bool lampAuto; // if true in conjunction with usePir & useLamp, switch on lamp when PIR activated
extern bool lampNight;
extern int lampType;
extern bool servoUse; // true to use pan / tilt servo control
extern bool voltUse; // true to report on ADC pin eg for for battery
// microphone cannot be used on IO Extender
extern bool micUse; // true to use external I2S microphone
extern bool wakeUse;

// sensors
extern int pirPin; // if usePir is true
extern bool pirVal;
extern int lampPin; // if useLamp is true
extern int wakePin; // if wakeUse is true

// Pan / Tilt Servos
extern int servoPanPin; // if useServos is true
extern int servoTiltPin;
Expand Down Expand Up @@ -254,7 +264,10 @@ extern TaskHandle_t servoHandle;
extern TaskHandle_t uartClientHandle;
extern TaskHandle_t emailHandle;
extern TaskHandle_t ftpHandle;
extern SemaphoreHandle_t frameMutex;
extern SemaphoreHandle_t motionMutex;


/************************** structures ********************************/

struct frameStruct {
Expand Down
31 changes: 24 additions & 7 deletions appSpecific.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,16 +55,19 @@ bool updateAppStatus(const char* variable, const char* value) {
else if(!strcmp(variable, "pirUse")) pirUse = (bool)intVal;
else if(!strcmp(variable, "lampLevel")) {
lampLevel = intVal;
if (!lampAuto) setLamp(lampLevel);
if (!lampType) setLamp(lampLevel); // manual
}
else if (!strcmp(variable, "lampUse")) {
lampUse = (bool)intVal;
if (!lampAuto) setLamp(lampLevel);
if (!lampType) setLamp(lampLevel); // manual
}
else if (!strcmp(variable, "lampAuto")) {
lampAuto = (bool)intVal;
if (lampAuto) setLamp(0);
else setLamp(lampLevel);
else if (!strcmp(variable, "lampType")) {
lampType = intVal;
lampAuto = lampNight = false;
if (lampType == 1) lampAuto = true;
if (lampType == 2) lampNight = true;
if (!lampType) setLamp(lampLevel); // manual
else setLamp(0);
}
else if(!strcmp(variable, "servoUse")) servoUse = (bool)intVal;
else if(!strcmp(variable, "voltUse")) voltUse = (bool)intVal;
Expand All @@ -88,7 +91,9 @@ bool updateAppStatus(const char* variable, const char* value) {
else if(!strcmp(variable, "voltInterval")) voltInterval = intVal;
else if(!strcmp(variable, "camPan")) setCamPan(intVal);
else if(!strcmp(variable, "camTilt")) setCamTilt(intVal);

else if(!strcmp(variable, "wakeUse")) wakeUse = (bool)intVal;
else if(!strcmp(variable, "wakePin")) wakePin = intVal;

// camera settings
else if(!strcmp(variable, "xclkMhz")) xclkMhz = intVal;
else if (s) {
Expand Down Expand Up @@ -212,4 +217,16 @@ bool appDataFiles() {

void doAppPing() {
doIOExtPing();
// check for night time actions
if (isNight(nightSwitch)) {
if (wakeUse && wakePin) {
// to use LDR on wake pin, connect it between pin and 3V3
// uses internal pulldown resistor as voltage divider
// but may need to add external pull down between pin
// and GND to alter required light level for wakeup
digitalWrite(PWDN_GPIO_NUM, 1); // power down camera
goToSleep(wakePin, true);
}
if (lampNight) setLamp(lampLevel);
} else if (lampNight) setLamp(0);
}
11 changes: 0 additions & 11 deletions globals.h
Original file line number Diff line number Diff line change
Expand Up @@ -105,9 +105,6 @@ void updateStatus(const char* variable, const char* _value);
void urlDecode(char* inVal);
uint32_t usePeripheral(const byte pinNum, const uint32_t receivedData);
void wsAsyncSend(const char* wsData);
void startMqttClient();
void stopMqttClient();
void mqttPublish(const char *payload);

/******************** Global utility declarations *******************/

Expand Down Expand Up @@ -155,14 +152,6 @@ extern char smtp_email[];
extern char smtp_server[];
extern uint16_t smtp_port;

// Mqtt broker
extern bool mqtt_active;
extern char mqtt_broker[];
extern char mqtt_port[];
extern char mqtt_user[];
extern char mqtt_user_Pass[];
extern char mqtt_topic_prefix[];

// control sending emails
extern size_t smtpBufferSize;
extern byte* SMTPbuffer;
Expand Down
40 changes: 21 additions & 19 deletions mjpeg2sd.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,10 @@ int tlPlaybackFPS; // rate to playback the timelapse, min 1
// status & control fields
uint8_t FPS;
bool nightTime = false;
bool autoUpload = false; // Automatically upload every created file to remote ftp server
bool autoUpload = false; // Automatically upload every created file to remote ftp server
uint8_t fsizePtr; // index to frameData[]
uint8_t minSeconds = 5; // default min video length (includes POST_MOTION_TIME)
bool doRecording = true; // whether to capture to SD or not
bool doRecording = true; // whether to capture to SD or not
uint8_t xclkMhz = 20; // camera clock rate MHz

// header and reporting info
Expand All @@ -43,7 +43,7 @@ static uint32_t oTime; // file opening time
static uint32_t cTime; // file closing time
static uint32_t sTime; // file streaming time

uint8_t frameDataRows = 14;
uint8_t frameDataRows = 14;
static uint16_t frameInterval; // units of 0.1ms between frames

// SD card storage
Expand Down Expand Up @@ -174,7 +174,7 @@ static void timeLapse(camera_fb_t* fb) {
buildAviIdx(jpegSize, true, true); // save avi index for frame
frameCntTL++;
intervalCnt = 0;
intervalMark = tlSecsBetweenFrames * saveFPS; // recalc in case FPS changed
intervalMark = tlSecsBetweenFrames * saveFPS; // recalc in case FPS changed
}
intervalCnt++;
if (frameCntTL > requiredFrames) {
Expand All @@ -196,6 +196,7 @@ static void timeLapse(camera_fb_t* fb) {
SD_MMC.rename(TLTEMP, TLname);
frameCntTL = intervalCnt = 0;
LOG_DBG("Finished time lapse");
if (autoUpload) ftpFileOrFolder(TLname); // Upload it to remote ftp server if requested
}
}
} else frameCntTL = intervalCnt = 0;
Expand Down Expand Up @@ -313,11 +314,11 @@ static bool closeAvi() {
LOG_INF("File open / completion times: %u ms / %u ms", oTime, cTime);
LOG_INF("Busy: %u%%", std::min(100 * (wTimeTot + fTimeTot + dTimeTot + oTime + cTime) / vidDuration, (uint32_t)100));
checkMemory();
LOG_INF("*************************************");
#ifdef INCLUDE_MQTT
sprintf(jsonBuff, "{\"%s\":\"%s\", \"%s\":\"%s\"}", "RECORD","OFF","TIME",esp_log_system_timestamp());
mqttPublish(jsonBuff);
#endif
LOG_INF("*************************************");
if (mqtt_active) {
sprintf(jsonBuff, "{\"RECORD\":\"OFF\", \"TIME\":\"%s\"}", esp_log_system_timestamp());
mqttPublish(jsonBuff);
}
if (autoUpload) ftpFileOrFolder(aviFileName); // Upload it to remote ftp server if requested
checkFreeSpace();
char subjectMsg[50];
Expand All @@ -327,15 +328,15 @@ static bool closeAvi() {
} else {
// delete too small files if exist
SD_MMC.remove(AVITEMP);
LOG_INF("Insufficient capture duration: %u secs", vidDurationSecs);
LOG_INF("Insufficient capture duration: %u secs", vidDurationSecs);
return false;
}
}

static boolean processFrame() {
// get camera frame
static bool wasCapturing = false;
static bool wasRecording = false;
static bool wasRecording = false;
static bool captureMotion = false;
bool res = true;
uint32_t dTime = millis();
Expand Down Expand Up @@ -365,10 +366,10 @@ static boolean processFrame() {
stopPlaying(); // terminate any playback
stopPlayback = true; // stop any subsequent playback
LOG_ALT("Capture started by %s%s%s", captureMotion ? "Motion " : "", pirVal ? "PIR" : "",forceRecord ? "Button" : "");
#ifdef INCLUDE_MQTT
sprintf(jsonBuff, "{\"%s\":\"%s\", \"%s\":\"%s\"}", "RECORD","ON","TIME",esp_log_system_timestamp());
mqttPublish(jsonBuff);
#endif
if (mqtt_active) {
sprintf(jsonBuff, "{\"RECORD\":\"ON\", \"TIME\":\"%s\"}", esp_log_system_timestamp());
mqttPublish(jsonBuff);
}
openAvi();
wasCapturing = true;
}
Expand Down Expand Up @@ -467,7 +468,7 @@ static void readSD() {
}
wTimeTot += millis() - rTime;
xSemaphoreGive(readSemaphore); // signal that ready
delay(10);
delay(10);
}


Expand Down Expand Up @@ -522,7 +523,7 @@ mjpegStruct getNextFrame(bool firstCall) {
LOG_DBG("SD wait time %lu ms", millis()-mTime);
wTimeTot += millis()-mTime;
mTime = millis();
// overlap buffer by CHUNK_HDR to prevent jpeg marker being split between buffers
// overlap buffer by CHUNK_HDR to prevent jpeg marker being split between buffers
memcpy(iSDbuffer+CHUNK_HDR, iSDbuffer+RAMSIZE+CHUNK_HDR, buffLen); // load new cluster from double buffer

LOG_DBG("memcpy took %lu ms for %u bytes", millis()-mTime, buffLen);
Expand Down Expand Up @@ -589,7 +590,7 @@ mjpegStruct getNextFrame(bool firstCall) {
LOG_INF("Average http send time: %u ms", hTimeTot / frameCnt);
LOG_INF("Busy: %u%%", min(100 * totBusy / (totBusy + tTimeTot), (uint32_t)100));
}
checkMemory();
checkMemory();
LOG_INF("*************************************\n");
setFPS(saveFPS); // realign with browser
stopPlayback = isPlaying = false;
Expand All @@ -601,6 +602,7 @@ mjpegStruct getNextFrame(bool firstCall) {
}

void stopPlaying() {
isStreaming = false; // if on another browser instance
if (isPlaying) {
// force stop any currently running playback
stopPlayback = true;
Expand Down Expand Up @@ -646,7 +648,7 @@ bool prepRecording() {
readSemaphore = xSemaphoreCreateBinary();
playbackSemaphore = xSemaphoreCreateBinary();
aviMutex = xSemaphoreCreateMutex();
motionMutex = xSemaphoreCreateMutex();
motionMutex = xSemaphoreCreateMutex();
camera_fb_t* fb = esp_camera_fb_get();
if (fb == NULL) LOG_WRN("failed to get camera frame");
else {
Expand Down
12 changes: 6 additions & 6 deletions motionDetect.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ static size_t jpgImgSize = 0;

static bool jpg2rgb(const uint8_t *src, size_t src_len, uint8_t ** out, jpg_scale_t scale);

static bool isNight(uint8_t nightSwitch) {
bool isNight(uint8_t nightSwitch) {
// check if night time for suspending recording
// or for switching on lamp if enabled
static bool nightTime = false;
Expand Down Expand Up @@ -136,8 +136,8 @@ bool checkMotion(camera_fb_t* fb, bool motionStatus) {
if (!motionStatus && motionCnt >= detectMotionFrames) {
LOG_DBG("***** Motion - START");
motionStatus = true; // motion started
if(mqtt_active){
sprintf(jsonBuff, "{\"%s\":\"%s\", \"%s\":\"%s\"}", "MOTION","ON","TIME",esp_log_system_timestamp());
if (mqtt_active) {
sprintf(jsonBuff, "{\"MOTION\":\"ON\",\"TIME\":\"%s\"}",esp_log_system_timestamp());
mqttPublish(jsonBuff);
}
}
Expand All @@ -151,9 +151,9 @@ bool checkMotion(camera_fb_t* fb, bool motionStatus) {
LOG_DBG("***** Motion - STOP after %u frames", motionCnt);
motionCnt = 0;
motionStatus = false; // motion stopped
if(mqtt_active){
sprintf(jsonBuff, "{\"%s\":\"%s\", \"%s\":\"%s\"}", "MOTION","OFF","TIME",esp_log_system_timestamp());
mqttPublish(jsonBuff);
if (mqtt_active) {
sprintf(jsonBuff, "{\"MOTION\":\"OFF\",\"TIME\":\"%s\"}", esp_log_system_timestamp());
mqttPublish(jsonBuff);
}
}
}
Expand Down
Loading

0 comments on commit 10cb064

Please sign in to comment.