delete shoulder camera zip

This commit is contained in:
brentru 2024-02-09 12:20:30 -05:00
parent ae08e5704c
commit dc64e09d61
30 changed files with 4630 additions and 0 deletions

View file

@ -0,0 +1,5 @@
.pio
.vscode/.browse.c_cpp.db*
.vscode/c_cpp_properties.json
.vscode/launch.json
.vscode/ipch

View file

@ -0,0 +1,10 @@
{
// See http://go.microsoft.com/fwlink/?LinkId=827846
// for the documentation about the extensions.json format
"recommendations": [
"platformio.platformio-ide"
],
"unwantedRecommendations": [
"ms-vscode.cpptools-extension-pack"
]
}

View file

@ -0,0 +1,3 @@
{
"cmake.configureOnOpen": true
}

View file

@ -0,0 +1,39 @@
This directory is intended for project header files.
A header file is a file containing C declarations and macro definitions
to be shared between several project source files. You request the use of a
header file in your project source file (C, C++, etc) located in `src` folder
by including it, with the C preprocessing directive `#include'.
```src/main.c
#include "header.h"
int main (void)
{
...
}
```
Including a header file produces the same results as copying the header file
into each source file that needs it. Such copying would be time-consuming
and error-prone. With a header file, the related declarations appear
in only one place. If they need to be changed, they can be changed in one
place, and programs that include the header file will automatically use the
new version when next recompiled. The header file eliminates the labor of
finding and changing all the copies as well as the risk that a failure to
find one copy will result in inconsistencies within a program.
In C, the usual convention is to give header files names that end with `.h'.
It is most portable to use only letters, digits, dashes, and underscores in
header file names, and at most one dot.
Read more about using header files in official GCC documentation:
* Include Syntax
* Include Operation
* Once-Only Headers
* Computed Includes
https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html

View file

@ -0,0 +1,46 @@
Thank you for opening an issue on an Adafruit Arduino library repository. To
improve the speed of resolution please review the following guidelines and
common troubleshooting steps below before creating the issue:
- **Do not use GitHub issues for troubleshooting projects and issues.** Instead use
the forums at http://forums.adafruit.com to ask questions and troubleshoot why
something isn't working as expected. In many cases the problem is a common issue
that you will more quickly receive help from the forum community. GitHub issues
are meant for known defects in the code. If you don't know if there is a defect
in the code then start with troubleshooting on the forum first.
- **If following a tutorial or guide be sure you didn't miss a step.** Carefully
check all of the steps and commands to run have been followed. Consult the
forum if you're unsure or have questions about steps in a guide/tutorial.
- **For Arduino projects check these very common issues to ensure they don't apply**:
- For uploading sketches or communicating with the board make sure you're using
a **USB data cable** and **not** a **USB charge-only cable**. It is sometimes
very hard to tell the difference between a data and charge cable! Try using the
cable with other devices or swapping to another cable to confirm it is not
the problem.
- **Be sure you are supplying adequate power to the board.** Check the specs of
your board and plug in an external power supply. In many cases just
plugging a board into your computer is not enough to power it and other
peripherals.
- **Double check all soldering joints and connections.** Flakey connections
cause many mysterious problems. See the [guide to excellent soldering](https://learn.adafruit.com/adafruit-guide-excellent-soldering/tools) for examples of good solder joints.
- **Ensure you are using an official Arduino or Adafruit board.** We can't
guarantee a clone board will have the same functionality and work as expected
with this code and don't support them.
If you're sure this issue is a defect in the code and checked the steps above
please fill in the following fields to provide enough troubleshooting information.
You may delete the guideline and text above to just leave the following details:
- Arduino board: **INSERT ARDUINO BOARD NAME/TYPE HERE**
- Arduino IDE version (found in Arduino -> About Arduino menu): **INSERT ARDUINO
VERSION HERE**
- List the steps to reproduce the problem below (if possible attach a sketch or
copy the sketch code in too): **LIST REPRO STEPS BELOW**

View file

@ -0,0 +1,26 @@
Thank you for creating a pull request to contribute to Adafruit's GitHub code!
Before you open the request please review the following guidelines and tips to
help it be more easily integrated:
- **Describe the scope of your change--i.e. what the change does and what parts
of the code were modified.** This will help us understand any risks of integrating
the code.
- **Describe any known limitations with your change.** For example if the change
doesn't apply to a supported platform of the library please mention it.
- **Please run any tests or examples that can exercise your modified code.** We
strive to not break users of the code and running tests/examples helps with this
process.
Thank you again for contributing! We will try to test and integrate the change
as soon as we can, but be aware we have many GitHub repositories to manage and
can't immediately respond to every request. There is no need to bump or check in
on a pull request (it will clutter the discussion of the request).
Also don't be worried if the request is closed or not integrated--sometimes the
priorities of Adafruit's GitHub code (education, ease of use) might not match the
priorities of the pull request. Don't fret, the open source community thrives on
forks and GitHub makes it easy to keep your changes in a forked repo.
After reviewing the guidelines above you can delete this text from the pull request.

View file

@ -0,0 +1,44 @@
name: Arduino Library CI
on: [pull_request, push, repository_dispatch]
jobs:
build:
runs-on: ubuntu-latest
steps:
- uses: actions/setup-python@v4
with:
python-version: '3.x'
- uses: actions/checkout@v3
- uses: actions/checkout@v3
with:
repository: adafruit/ci-arduino
path: ci
- name: pre-install
run: bash ci/actions_install.sh
- name: test platforms
run: python3 ci/build_platform.py "pycamera_s3"
- name: list
run: |
ls
ls examples/*/build/
- name: Upload build artifacts
uses: actions/upload-artifact@v3
with:
name: example_uf2s
path: |
examples/*/build/*/*.uf2
- name: clang
run: python3 ci/run-clang-format.py -e "ci/*" -e "bin/*" -r .
- name: doxygen
env:
GH_REPO_TOKEN: ${{ secrets.GH_REPO_TOKEN }}
PRETTYNAME : "Adafruit PyCamera Library"
run: bash ci/doxy_gen_and_deploy.sh

View file

@ -0,0 +1,869 @@
#include "Adafruit_PyCamera.h"
static uint16_t *jpeg_buffer = NULL;
/**************************************************************************/
/**
* @brief Outputs the buffer for JPEG decoding.
*
* @param x The x-coordinate where the bitmap starts.
* @param y The y-coordinate where the bitmap starts.
* @param w The width of the bitmap.
* @param h The height of the bitmap.
* @param bitmap Pointer to the bitmap data.
*
* @return true if the buffer is successfully outputted, false otherwise.
*
* @details This function is used as a callback for JPEG decoding. It outputs
* the decoded bitmap to a specified location in the `jpeg_buffer`. The function
* checks for the validity of `jpeg_buffer` and ensures that the drawing
* operations stay within the bounds of the buffer.
*/
/**************************************************************************/
bool buffer_output(int16_t x, int16_t y, uint16_t w, uint16_t h,
uint16_t *bitmap) {
if (!jpeg_buffer)
return false;
// Serial.printf("Drawing [%d, %d] to (%d, %d)\n", w, h, x, y);
for (int xi = x; xi < x + w; xi++) {
if (xi >= 240)
continue;
if (xi < 0)
continue;
for (int yi = y; yi < y + h; yi++) {
if (yi >= 240)
continue;
if (yi < 0)
continue;
jpeg_buffer[yi * 240 + xi] = bitmap[(yi - y) * w + (xi - x)];
}
}
return true;
}
/**************************************************************************/
/**
* @brief Construct a new Adafruit_PyCamera object.
*
* @details Initializes the display with specified TFT parameters.
*
*/
/**************************************************************************/
Adafruit_PyCamera::Adafruit_PyCamera(void)
: Adafruit_ST7789(TFT_CS, TFT_DC, TFT_RESET) {}
/**************************************************************************/
/**
* @brief Initializes the PyCamera.
*
* @details Sets up the speaker, Neopixel, Neopixel Ring, shutter button, and
* performs I2C scan. Initializes the display, expander, camera, frame size, SD
* card (if detected), and accelerometer. Creates a new framebuffer for the
* camera.
*
* @return true if initialization is successful, false otherwise.
*/
/**************************************************************************/
bool Adafruit_PyCamera::begin() {
Serial.println("Init PyCamera obj");
// Setup and turn off speaker
pinMode(SPEAKER, OUTPUT);
digitalWrite(SPEAKER, LOW);
// Setup and turn off Neopixel
pixel.setPin(PIN_NEOPIXEL);
pixel.updateLength(1);
pixel.begin();
pixel.setBrightness(50);
setNeopixel(0x0);
// Setup and turn off Neopixel Ring
ring.setPin(A1);
ring.updateType(NEO_GRBW + NEO_KHZ800);
ring.updateLength(8);
ring.begin();
ring.setBrightness(255);
setRing(0x0);
// boot button is also shutter
pinMode(SHUTTER_BUTTON, INPUT_PULLUP);
I2Cscan();
if (!initDisplay())
return false;
if (!initExpander())
return false;
if (!initCamera(true))
return false;
if (!setFramesize(FRAMESIZE_240X240))
return false;
if (SDdetected())
initSD();
if (!initAccel())
return false;
fb = new PyCameraFB(240, 240);
_timestamp = millis();
return true;
}
/**************************************************************************/
/**
* @brief Initializes the SD card.
*
* @details Checks for SD card presence and attempts initialization. Performs a
* power reset, reinitializes SPI for SD card communication, and checks for
* errors during SD card initialization. Also lists files on the SD card if
* initialization is successful.
*
* @return true if SD card is successfully initialized, false otherwise.
*/
/**************************************************************************/
bool Adafruit_PyCamera::initSD(void) {
if (!SDdetected()) {
Serial.println("No SD card inserted");
return false;
}
Serial.println("SD card inserted, trying to init");
// power reset
aw.pinMode(AWEXP_SD_PWR, OUTPUT);
aw.digitalWrite(AWEXP_SD_PWR, HIGH); // turn off
pinMode(SD_CS, OUTPUT);
digitalWrite(SD_CS, LOW);
Serial.println("De-initing SPI");
SPI.end();
pinMode(SCK, OUTPUT);
digitalWrite(SCK, LOW);
pinMode(MOSI, OUTPUT);
digitalWrite(MISO, LOW);
pinMode(MISO, OUTPUT);
digitalWrite(MISO, LOW);
delay(50);
Serial.println("Re-init SPI");
digitalWrite(SD_CS, HIGH);
SPI.begin();
aw.digitalWrite(AWEXP_SD_PWR, LOW); // turn on
delay(100);
if (!sd.begin(SD_CS, SD_SCK_MHZ(4))) {
if (sd.card()->errorCode()) {
Serial.printf("SD card init failure with code 0x%x data %d\n",
sd.card()->errorCode(), (int)sd.card()->errorData());
} else if (sd.vol()->fatType() == 0) {
Serial.println("Can't find a valid FAT16/FAT32 partition.");
} else {
Serial.println("SD begin failed, can't determine error type");
}
aw.digitalWrite(AWEXP_SD_PWR, HIGH); // turn off power
return false;
}
Serial.println("Card successfully initialized");
uint32_t size = sd.card()->cardSize();
if (size == 0) {
Serial.println("Can't determine the card size");
} else {
uint32_t sizeMB = 0.000512 * size + 0.5;
Serial.printf("Card size: %d MB FAT%d\n", (int)sizeMB, sd.vol()->fatType());
}
Serial.println("Files found (date time size name):");
sd.ls(LS_R | LS_DATE | LS_SIZE);
return true;
}
/**************************************************************************/
/**
* @brief Ends the SD card session.
*
* @details Powers off the SD card to end the session.
*/
/**************************************************************************/
void Adafruit_PyCamera::endSD() {
// aw.pinMode(AWEXP_SD_PWR, OUTPUT);
// aw.digitalWrite(AWEXP_SD_PWR, HIGH); // start off
}
/**************************************************************************/
/**
* @brief Initializes the AW9523 I/O expander.
*
* @details Sets up the AW9523 expander, configuring speaker, SD power, and SD
* detection pins.
*
* @return true if the expander is successfully initialized, false otherwise.
*/
/**************************************************************************/
bool Adafruit_PyCamera::initExpander(void) {
Serial.print("Init AW9523...");
if (!aw.begin(0x58, &Wire)) {
Serial.println("AW9523 not found!");
return false;
}
Serial.println("OK!");
aw.pinMode(AWEXP_SPKR_SD, OUTPUT);
aw.digitalWrite(AWEXP_SPKR_SD, LOW); // start muted
aw.pinMode(AWEXP_SD_PWR, OUTPUT);
aw.digitalWrite(AWEXP_SD_PWR, LOW); // start SD powered
aw.pinMode(AWEXP_SD_DET, INPUT);
return true;
}
/**************************************************************************/
/**
* @brief Initializes the display.
*
* @details This method sets up the display for the PyCamera. It starts by
* initializing the backlight control, then initializes the ST7789 screen with
* the specified dimensions and rotation. Finally, it fills the screen with a
* green color and turns on the backlight.
*
* @return true if the display is successfully initialized, false otherwise.
*/
/**************************************************************************/
bool Adafruit_PyCamera::initDisplay(void) {
Serial.print("Init display....");
pinMode(TFT_BACKLIGHT, OUTPUT);
digitalWrite(TFT_BACKLIGHT, LOW);
init(240, 240); // Initialize ST7789 screen
setRotation(1);
fillScreen(ST77XX_GREEN);
digitalWrite(TFT_BACKLIGHT, HIGH);
Serial.println("done!");
return true;
}
/**************************************************************************/
/**
* @brief Sets the frame size for the camera.
*
* @details Configures the camera to use the specified frame size. If the frame
* size cannot be set, it outputs an error message with the error code.
*
* @param framesize The desired frame size to set for the camera.
* @return true if the frame size is successfully set, false if there is an
* error.
*/
/**************************************************************************/
bool Adafruit_PyCamera::setFramesize(framesize_t framesize) {
uint8_t ret = camera->set_framesize(camera, framesize);
if (ret != 0) {
Serial.printf("Could not set resolution: error 0x%x\n", ret);
return false;
}
return true;
}
/**************************************************************************/
/**
* @brief Sets a special effect on the camera.
*
* @details Applies a specified special effect to the camera's output. If the
* effect cannot be set, it outputs an error message with the error code.
*
* @param effect The special effect identifier to apply.
* @return true if the special effect is successfully set, false if there is an
* error.
*/
/**************************************************************************/
bool Adafruit_PyCamera::setSpecialEffect(uint8_t effect) {
uint8_t ret = camera->set_special_effect(camera, effect);
if (ret != 0) {
Serial.printf("Could not set effect: error 0x%x\n", ret);
return false;
}
return true;
}
/**************************************************************************/
/**
* @brief Initializes the camera module.
*
* @details Configures and initializes the camera with specified settings.
* It sets up various camera parameters like LEDC channel and timer, pin
* configuration, XCLK frequency, frame buffer location, pixel format, frame
* size, and JPEG quality. It also handles the hardware reset if specified.
* After configuration, it initializes the camera and checks for errors. If
* successful, it retrieves the camera sensor information and sets horizontal
* mirror and vertical flip settings.
*
* @param hwreset Flag to determine if a hardware reset is needed.
* @return true if the camera is successfully initialized, false if there is an
* error.
*/
/**************************************************************************/
bool Adafruit_PyCamera::initCamera(bool hwreset) {
Serial.print("Config camera...");
Wire.begin(PYCAM_SDA, PYCAM_SCL);
if (hwreset) {
}
camera_config.ledc_channel = LEDC_CHANNEL_0;
camera_config.ledc_timer = LEDC_TIMER_0;
camera_config.pin_d0 = Y2_GPIO_NUM;
camera_config.pin_d1 = Y3_GPIO_NUM;
camera_config.pin_d2 = Y4_GPIO_NUM;
camera_config.pin_d3 = Y5_GPIO_NUM;
camera_config.pin_d4 = Y6_GPIO_NUM;
camera_config.pin_d5 = Y7_GPIO_NUM;
camera_config.pin_d6 = Y8_GPIO_NUM;
camera_config.pin_d7 = Y9_GPIO_NUM;
camera_config.pin_xclk = XCLK_GPIO_NUM;
camera_config.pin_pclk = PCLK_GPIO_NUM;
camera_config.pin_vsync = VSYNC_GPIO_NUM;
camera_config.pin_href = HREF_GPIO_NUM;
camera_config.pin_sccb_sda = -1;
camera_config.pin_sccb_scl = -1;
// use the built in I2C port
camera_config.sccb_i2c_port = 0; // use the 'first' i2c port
camera_config.pin_pwdn = 21;
camera_config.pin_reset = 47;
camera_config.xclk_freq_hz = 20000000;
camera_config.grab_mode = CAMERA_GRAB_WHEN_EMPTY;
camera_config.fb_location = CAMERA_FB_IN_PSRAM;
Serial.print("Config format...");
/*
// using RGB565 for immediate blitting
camera_config.pixel_format = PIXFORMAT_RGB565;
camera_config.frame_size = FRAMESIZE_240X240;
camera_config.fb_count = 1;
*/
camera_config.pixel_format = PIXFORMAT_JPEG;
camera_config.frame_size =
FRAMESIZE_UXGA; // start with biggest possible image supported!!! do not
// change this
camera_config.jpeg_quality = 4;
camera_config.fb_count = 2;
Serial.print("Initializing...");
// camera init
esp_err_t err = esp_camera_init(&camera_config);
if (err != ESP_OK) {
Serial.printf("Camera init failed with error 0x%x\n\r", err);
return false;
}
Serial.println("OK");
camera = esp_camera_sensor_get();
Serial.printf("Found camera PID %04X\n\r", camera->id.PID);
camera->set_hmirror(camera, 0);
camera->set_vflip(camera, 1);
return true;
}
/**************************************************************************/
/**
* @brief Reads the battery voltage.
*
* @details Measures the battery voltage through the BATT_MONITOR pin.
* The reading is scaled to account for the voltage divider and ADC resolution.
*
* @return The battery voltage in volts.
*/
/**************************************************************************/
float Adafruit_PyCamera::readBatteryVoltage(void) {
return analogRead(BATT_MONITOR) * 2.0 * 3.3 / 4096;
}
/**************************************************************************/
/**
* @brief Checks if an SD card is detected.
*
* @details Reads the state of the SD card detection pin using the AW9523
* expander. A high state indicates that an SD card is present.
*
* @return true if an SD card is detected, false otherwise.
*/
/**************************************************************************/
bool Adafruit_PyCamera::SDdetected(void) {
return aw.digitalRead(AWEXP_SD_DET);
}
/**************************************************************************/
/**
* @brief Reads the current state of the buttons.
*
* @details Retrieves the state of all buttons connected to the AW9523 expander
* and the shutter button. The state is updated and stored in the button_state
* variable. The previous state is stored in last_button_state.
*
* @return The current state of the buttons as a 32-bit unsigned integer.
*/
/**************************************************************************/
uint32_t Adafruit_PyCamera::readButtons(void) {
last_button_state = button_state;
button_state = aw.inputGPIO() & AW_INPUTS_MASK;
button_state |= (bool)digitalRead(SHUTTER_BUTTON);
return button_state;
}
/**************************************************************************/
/**
* @brief Checks if a button was just pressed.
*
* @details Determines if the specified button has transitioned from a
* non-pressed to a pressed state since the last read. This function is useful
* for detecting button press events.
*
* @param button_pin The pin number of the button to check.
* @return true if the button was just pressed, false otherwise.
*/
/**************************************************************************/
bool Adafruit_PyCamera::justPressed(uint8_t button_pin) {
return ((last_button_state & (1UL << button_pin)) && // was not pressed before
!(button_state & (1UL << button_pin))); // and is pressed now
}
/**************************************************************************/
/**
* @brief Checks if a button was just released.
*
* @details Determines if the specified button has transitioned from a pressed
* to a non-pressed state since the last read. This function is useful for
* detecting button release events.
*
* @param button_pin The pin number of the button to check.
* @return true if the button was just released, false otherwise.
*/
/**************************************************************************/
bool Adafruit_PyCamera::justReleased(uint8_t button_pin) {
return (!(last_button_state & (1UL << button_pin)) && // was pressed before
(button_state & (1UL << button_pin))); // and isnt pressed now
}
/**************************************************************************/
/**
* @brief Plays a tone through the speaker.
*
* @details Generates a tone of a specified frequency and duration through the
* speaker. It unmutes the speaker before playing the tone and mutes it again
* after the tone is played. The function uses a blocking delay for the duration
* of the tone.
*
* @param tonefreq The frequency of the tone in Hertz.
* @param tonetime The duration of the tone in milliseconds.
*/
/**************************************************************************/
void Adafruit_PyCamera::speaker_tone(uint32_t tonefreq, uint32_t tonetime) {
aw.digitalWrite(AWEXP_SPKR_SD, HIGH); // un-mute
tone(SPEAKER, tonefreq, tonetime); // tone1 - B5
delay(tonetime);
aw.digitalWrite(AWEXP_SPKR_SD, LOW); // mute
}
/**************************************************************************/
/**
* @brief Captures a photo and saves it to an SD card.
*
* @details This function captures a photo with the camera at the specified
* resolution, and saves it to the SD card with a filename based on the provided
* base name. It handles SD card detection, initialization, and file creation.
* The function also manages camera frame buffer acquisition and release, and
* sets the camera resolution.
*
* @param filename_base Base name for the file to be saved. The function appends
* a numerical suffix to create a unique filename.
* @param framesize The resolution at which the photo should be captured.
* @return true if the photo is successfully captured and saved, false
* otherwise.
*/
/**************************************************************************/
bool Adafruit_PyCamera::takePhoto(const char *filename_base,
framesize_t framesize) {
bool ok = false;
File file;
// esp_err_t res = ESP_OK;
if (!SDdetected()) {
Serial.println("No SD card inserted");
return false;
}
if (!sd.card() || (sd.card()->cardSize() == 0)) {
Serial.println("No SD card found");
// try to initialize?
if (!initSD())
return false;
}
// we're probably going to succeed in saving the file so we should
// change rez now since we need to grab two frames worth to clear out a cache
Serial.println("Reconfiguring resolution");
if (!setFramesize(framesize))
return false;
// capture and toss first internal buffer
frame = esp_camera_fb_get();
if (!frame) {
esp_camera_fb_return(frame);
setFramesize(FRAMESIZE_240X240);
Serial.println("Couldnt capture first frame");
return false;
}
Serial.printf("\t\t\tSnapped 1st %d bytes (%d x %d) in %d ms\n\r", frame->len,
frame->width, frame->height, (int)timestamp());
esp_camera_fb_return(frame);
// capture and toss second internal buffer
frame = esp_camera_fb_get();
if (!frame) {
esp_camera_fb_return(frame);
Serial.println("Couldnt capture second frame");
setFramesize(FRAMESIZE_240X240);
return false;
}
Serial.printf("\t\t\tSnapped 2nd %d bytes (%d x %d) in %d ms\n\r", frame->len,
frame->width, frame->height, (int)timestamp());
char fullfilename[64];
for (int inc = 0; inc <= 1000; inc++) {
if (inc == 1000)
return false;
snprintf(fullfilename, sizeof(fullfilename), "%s%03d.jpg", filename_base,
inc);
if (!sd.exists(fullfilename))
break;
}
// Create the file
if (file.open(fullfilename, FILE_WRITE)) {
if (file.write(frame->buf, frame->len)) {
Serial.printf("Saved JPEG to filename %s\n\r", fullfilename);
file.close();
// check what we wrote!
sd.ls(LS_R | LS_DATE | LS_SIZE);
ok = true;
} else {
Serial.println("Couldn't write JPEG data to file");
}
}
// even if it doesnt work out, reset camera size and close file
esp_camera_fb_return(frame);
file.close();
setFramesize(FRAMESIZE_240X240);
return ok;
}
/**************************************************************************/
/**
* @brief Returns the time elapsed since the last call to this function.
*
* @details This function calculates the time difference (in milliseconds)
* between the current time and the last time this function was called. It
* updates the internal timestamp to the current time at each call.
*
* @return The time elapsed (in milliseconds) since the last call to this
* function.
*/
/**************************************************************************/
uint32_t Adafruit_PyCamera::timestamp(void) {
uint32_t delta = millis() - _timestamp;
_timestamp = millis();
return delta;
}
/**************************************************************************/
/**
* @brief Prints a timestamped message to the Serial output.
*
* @details This function prints a message to the Serial output, prefixed with a
* timestamp. The timestamp represents the time elapsed in milliseconds since
* the last call to `timestamp()` function. It is useful for debugging and
* performance measurement.
*
* @param msg The message to be printed along with the timestamp.
*/
/**************************************************************************/
void Adafruit_PyCamera::timestampPrint(const char *msg) {
Serial.printf("%s: %d ms elapsed\n\r", msg, (int)timestamp());
}
/**************************************************************************/
/**
* @brief Captures a frame from the camera and processes it.
*
* @details This function captures a frame from the camera and processes it
* based on the current pixel format setting. It handles both JPEG and RGB565
* formats. For JPEG, it scales and draws the image onto a framebuffer. For
* RGB565, it flips the endians of the frame buffer. This function is essential
* for capturing and displaying camera frames.
*
* @return bool Returns true if the frame was successfully captured and
* processed, false otherwise.
*/
/**************************************************************************/
bool Adafruit_PyCamera::captureFrame(void) {
// Serial.println("Capturing...");
// esp_err_t res = ESP_OK;
#if ARDUHAL_LOG_LEVEL >= ARDUHAL_LOG_LEVEL_INFO
int64_t fr_start = esp_timer_get_time();
#endif
frame = esp_camera_fb_get();
if (!frame) {
ESP_LOGE(TAG, "Camera frame capture failed");
return false;
}
/*
Serial.printf("\t\t\tFramed %d bytes (%d x %d) in %d ms\n\r",
frame->len,
frame->width, frame->height,
timestamp());
*/
if (camera_config.pixel_format == PIXFORMAT_JPEG) {
// Serial.print("JPEG");
// create the framebuffer if we haven't yet
if (!fb->getBuffer() || !jpeg_buffer) {
jpeg_buffer = (uint16_t *)malloc(240 * 240 * 2);
fb->setFB(jpeg_buffer);
}
uint16_t w = 0, h = 0, scale = 1;
int xoff = 0, yoff = 0;
TJpgDec.getJpgSize(&w, &h, frame->buf, frame->len);
if (w <= 240 || h <= 240) {
scale = 1;
xoff = yoff = 0;
} else if (w <= 480 || h <= 480) {
scale = 2;
xoff = (480 - w) / 2;
yoff = (480 - h) / 2;
} else if (w <= 960 || h <= 960) {
scale = 4;
} else {
scale = 8;
}
// Serial.printf(" size: %d x %d, scale %d\n\r", w, h, scale);
TJpgDec.setJpgScale(scale);
TJpgDec.setCallback(buffer_output);
TJpgDec.drawJpg(xoff, yoff, frame->buf, frame->len);
fb->setFB(jpeg_buffer);
} else if (camera_config.pixel_format == PIXFORMAT_RGB565) {
// flip endians
uint8_t temp;
for (uint32_t i = 0; i < frame->len; i += 2) {
temp = frame->buf[i + 0];
frame->buf[i + 0] = frame->buf[i + 1];
frame->buf[i + 1] = temp;
}
fb->setFB((uint16_t *)frame->buf);
}
return true;
}
/**************************************************************************/
/**
* @brief Blits the current frame buffer to the display.
*
* @details This function draws the current frame buffer onto the display at the
* specified coordinates. It is used to update the display with the latest
* camera frame. After drawing, it returns the frame buffer to the camera for
* reuse.
*/
/**************************************************************************/
void Adafruit_PyCamera::blitFrame(void) {
drawRGBBitmap(0, 0, (uint16_t *)fb->getBuffer(), 240, 240);
esp_camera_fb_return(frame);
}
/**************************************************************************/
/**
* @brief Initializes the accelerometer.
*
* @details This function initializes the accelerometer by setting up the I2C
* device, checking the chip ID, and configuring the control registers for
* normal mode, data rate, resolution, and range. It ensures that the
* accelerometer is ready for data reading.
*
* @return bool Returns true if the accelerometer is successfully initialized,
* false otherwise.
*/
/**************************************************************************/
bool Adafruit_PyCamera::initAccel(void) {
lis_dev = new Adafruit_I2CDevice(0x19, &Wire);
if (!lis_dev->begin()) {
return false;
}
Adafruit_BusIO_Register _chip_id =
Adafruit_BusIO_Register(lis_dev, LIS3DH_REG_WHOAMI, 1);
if (_chip_id.read() != 0x33) {
return false;
}
Adafruit_BusIO_Register _ctrl1 =
Adafruit_BusIO_Register(lis_dev, LIS3DH_REG_CTRL1, 1);
_ctrl1.write(0x07); // enable all axes, normal mode
Adafruit_BusIO_RegisterBits data_rate_bits =
Adafruit_BusIO_RegisterBits(&_ctrl1, 4, 4);
data_rate_bits.write(0b0111); // set to 400Hz update
Adafruit_BusIO_Register _ctrl4 =
Adafruit_BusIO_Register(lis_dev, LIS3DH_REG_CTRL4, 1);
_ctrl4.write(0x88); // High res & BDU enabled
Adafruit_BusIO_RegisterBits range_bits =
Adafruit_BusIO_RegisterBits(&_ctrl4, 2, 4);
range_bits.write(0b11);
Serial.println("Found LIS3DH");
return true;
}
/**************************************************************************/
/**
* @brief Reads accelerometer data.
*
* @details This function reads the X, Y, and Z acceleration data from the
* accelerometer. It sets up the register address for auto-increment to read
* consecutive data registers and then reads the 6 bytes of data corresponding
* to the X, Y, and Z axes.
*
* @param[out] x Pointer to store the X-axis acceleration data.
* @param[out] y Pointer to store the Y-axis acceleration data.
* @param[out] z Pointer to store the Z-axis acceleration data.
* @return bool Returns true if the data is successfully read, false otherwise.
*/
/**************************************************************************/
bool Adafruit_PyCamera::readAccelData(int16_t *x, int16_t *y, int16_t *z) {
uint8_t register_address = LIS3DH_REG_OUT_X_L;
register_address |= 0x80; // set [7] for auto-increment
Adafruit_BusIO_Register xl_data =
Adafruit_BusIO_Register(lis_dev, register_address, 6);
uint8_t buffer[6];
if (!xl_data.read(buffer, 6))
return false;
*x = buffer[0];
*x |= ((uint16_t)buffer[1]) << 8;
*y = buffer[2];
*y |= ((uint16_t)buffer[3]) << 8;
*z = buffer[4];
*z |= ((uint16_t)buffer[5]) << 8;
return true;
}
/**************************************************************************/
/**
* @brief Reads accelerometer data and converts it to g-force values.
*
* @details This function reads the raw accelerometer data for X, Y, and Z axes
* using readAccelData() and then converts these values to g-force. The
* conversion factor depends on the accelerometer's sensitivity setting (here
* assumed for 16G range).
*
* @param[out] x_g Pointer to store the X-axis acceleration in g-force.
* @param[out] y_g Pointer to store the Y-axis acceleration in g-force.
* @param[out] z_g Pointer to store the Z-axis acceleration in g-force.
* @return bool Returns true if the data is successfully read and converted,
* false otherwise.
*/
/**************************************************************************/
bool Adafruit_PyCamera::readAccelData(float *x_g, float *y_g, float *z_g) {
int16_t x, y, z;
if (!readAccelData(&x, &y, &z))
return false;
uint8_t lsb_value = 48; // for 16G
*x_g = lsb_value * ((float)x / LIS3DH_LSB16_TO_KILO_LSB10);
*y_g = lsb_value * ((float)y / LIS3DH_LSB16_TO_KILO_LSB10);
*z_g = lsb_value * ((float)z / LIS3DH_LSB16_TO_KILO_LSB10);
return true;
}
/**************************************************************************/
/**
* @brief Scans the I2C bus and prints the addresses of all connected devices.
*
* @details This function iterates through all possible I2C addresses (0x00 to
* 0x7F) and attempts to initiate a transmission to each. If a device
* acknowledges the transmission, its address is printed to the Serial output.
* This is useful for debugging and identifying connected I2C devices.
*/
/**************************************************************************/
void Adafruit_PyCamera::I2Cscan(void) {
Wire.begin(PYCAM_SDA, PYCAM_SCL);
Serial.print("I2C Scan: ");
for (int addr = 0; addr <= 0x7F; addr++) {
Wire.beginTransmission(addr);
bool found = (Wire.endTransmission() == 0);
if (found) {
Serial.print("0x");
Serial.print(addr, HEX);
Serial.print(", ");
}
}
Serial.println();
}
/**************************************************************************/
/**
* @brief Sets the color of the Neopixel.
*
* @param c The color to set the Neopixel to, in 32-bit RGB format.
*
* @details This function sets the color of the Neopixel LED. It uses the `fill`
* method of the Adafruit_NeoPixel class to set all pixels to the specified
* color and then calls `show` to update the LED with the new color.
*/
/**************************************************************************/
void Adafruit_PyCamera::setNeopixel(uint32_t c) {
pixel.fill(c);
pixel.show(); // Initialize all pixels to 'off'
}
/**************************************************************************/
/**
* @brief Sets the color of the Neopixel Ring.
*
* @param c The color to set the Neopixel Ring to, in 32-bit RGB format.
*
* @details This function sets the color of the Neopixel Ring. It uses the
* `fill` method of the Adafruit_NeoPixel class to set all pixels in the ring to
* the specified color and then calls `show` to update the ring with the new
* color.
*/
/**************************************************************************/
void Adafruit_PyCamera::setRing(uint32_t c) {
ring.fill(c);
ring.show(); // Initialize all pixels to 'off'
}
/**************************************************************************/
/*!
@brief Input a value 0 to 255 to get a color value. The colours are a
transition r - g - b - back to r.
@param WheelPos The position in the wheel, from 0 to 255
@returns The 0xRRGGBB color
*/
/**************************************************************************/
uint32_t Adafruit_PyCamera::Wheel(byte WheelPos) {
WheelPos = 255 - WheelPos;
if (WheelPos < 85) {
return Adafruit_NeoPixel::Color(255 - WheelPos * 3, 0, WheelPos * 3);
}
if (WheelPos < 170) {
WheelPos -= 85;
return Adafruit_NeoPixel::Color(0, WheelPos * 3, 255 - WheelPos * 3);
}
WheelPos -= 170;
return Adafruit_NeoPixel::Color(WheelPos * 3, 255 - WheelPos * 3, 0);
}

View file

@ -0,0 +1,164 @@
#include "TJpg_Decoder.h"
#include "esp_camera.h"
#include <Adafruit_AW9523.h>
#include <Adafruit_NeoPixel.h>
#include <Adafruit_ST7789.h> // Hardware-specific library for ST7789
#include <SdFat.h>
#ifndef TAG
#define TAG "PYCAM"
#endif
// These are defined within https://github.com/espressif/arduino-esp32/blob/master/variants/adafruit_camera_esp32s3/pins_arduino.h
// However, they are not updated to the production-ready pins within the PlatformIO ESP32 package, so we define them here.
#define TFT_BACKLIGHT 45
#define PYCAM_SCL 33
#define PYCAM_SDA 34
#define AW_DOWN_MASK (1UL << AWEXP_BUTTON_DOWN)
#define AW_LEFT_MASK (1UL << AWEXP_BUTTON_LEFT)
#define AW_UP_MASK (1UL << AWEXP_BUTTON_UP)
#define AW_RIGHT_MASK (1UL << AWEXP_BUTTON_RIGHT)
#define AW_OK_MASK (1UL << AWEXP_BUTTON_OK)
#define AW_SEL_MASK (1UL << AWEXP_BUTTON_SEL)
#define AW_CARDDET_MASK (1UL << AWEXP_SD_DET)
#define AW_INPUTS_MASK \
(AW_DOWN_MASK | AW_LEFT_MASK | AW_UP_MASK | AW_RIGHT_MASK | AW_OK_MASK | \
AW_SEL_MASK | AW_CARDDET_MASK)
/**************************************************************************/
/**
* @brief Framebuffer class for PyCamera.
*
* @details This class extends GFXcanvas16 to provide a framebuffer for the
* PyCamera.
*/
/**************************************************************************/
class PyCameraFB : public GFXcanvas16 {
public:
/**************************************************************************/
/**
* @brief Construct a new PyCameraFB object.
*
* @param w Width of the framebuffer.
* @param h Height of the framebuffer.
*/
/**************************************************************************/
PyCameraFB(uint16_t w, uint16_t h) : GFXcanvas16(w, h) {
free(buffer);
buffer = NULL;
};
/**************************************************************************/
/**
* @brief Set the framebuffer.
*
* @param fb Pointer to the framebuffer data.
*/
/**************************************************************************/
void setFB(uint16_t *fb) { buffer = fb; }
};
/**************************************************************************/
/**
* @brief Main class for Adafruit PyCamera.
*
* @details This class extends Adafruit_ST7789 and provides functionalities
* for operating the PyCamera.
*/
/**************************************************************************/
class Adafruit_PyCamera : public Adafruit_ST7789 {
public:
/**************************************************************************/
/**
* @brief Construct a new Adafruit_PyCamera object.
*/
/**************************************************************************/
Adafruit_PyCamera();
bool begin(void);
bool initCamera(bool hwreset);
bool initDisplay(void);
bool initExpander(void);
bool initAccel(void);
bool initSD(void);
void endSD(void);
void I2Cscan(void);
bool captureFrame(void);
void blitFrame(void);
bool takePhoto(const char *filename_base, framesize_t framesize);
bool setFramesize(framesize_t framesize);
bool setSpecialEffect(uint8_t effect);
void speaker_tone(uint32_t tonefreq, uint32_t tonetime);
float readBatteryVoltage(void);
uint32_t readButtons(void);
bool SDdetected(void);
bool justReleased(uint8_t button_pin);
bool justPressed(uint8_t button_pin);
bool readAccelData(int16_t *x, int16_t *y, int16_t *z);
bool readAccelData(float *x, float *y, float *z);
void setNeopixel(uint32_t c);
void setRing(uint32_t c);
uint32_t Wheel(byte WheelPos);
uint32_t timestamp(void);
void timestampPrint(const char *msg);
/** @brief Pointer to the camera sensor structure. */
sensor_t *camera;
/** @brief Pointer to the camera frame buffer. */
camera_fb_t *frame = NULL;
/** @brief Pointer to the PyCamera framebuffer object. */
PyCameraFB *fb = NULL;
/** @brief Adafruit NeoPixel object for single pixel control. */
Adafruit_NeoPixel pixel;
/** @brief Adafruit NeoPixel object for ring control. */
Adafruit_NeoPixel ring;
/** @brief Adafruit AW9523 object for I/O expander functionality. */
Adafruit_AW9523 aw;
/** @brief Pointer to the I2C device for accelerometer. */
Adafruit_I2CDevice *lis_dev = NULL;
/** @brief SdFat object for SD card operations. */
SdFat sd;
/** @brief Timestamp for internal timing operations. */
uint32_t _timestamp;
/** @brief Last state of the buttons. */
uint32_t last_button_state = 0xFFFFFFFF;
/** @brief Current state of the buttons. */
uint32_t button_state = 0xFFFFFFFF;
/** @brief Current photo size setting. */
framesize_t photoSize = FRAMESIZE_VGA;
/** @brief Current special effect setting. */
int8_t specialEffect = 0;
/** @brief Configuration structure for the camera. */
camera_config_t camera_config;
};
#define LIS3DH_REG_STATUS1 0x07
#define LIS3DH_REG_OUTADC1_L 0x08 /**< 1-axis acceleration data. Low value */
#define LIS3DH_REG_OUTADC1_H 0x09 /**< 1-axis acceleration data. High value */
#define LIS3DH_REG_OUTADC2_L 0x0A /**< 2-axis acceleration data. Low value */
#define LIS3DH_REG_OUTADC2_H 0x0B /**< 2-axis acceleration data. High value */
#define LIS3DH_REG_OUTADC3_L 0x0C /**< 3-axis acceleration data. Low value */
#define LIS3DH_REG_OUTADC3_H 0x0D /**< 3-axis acceleration data. High value */
#define LIS3DH_REG_INTCOUNT \
0x0E /**< INT_COUNTER register [IC7, IC6, IC5, IC4, IC3, IC2, IC1, IC0] */
#define LIS3DH_REG_WHOAMI 0x0F
#define LIS3DH_REG_TEMPCFG 0x1F
#define LIS3DH_REG_CTRL1 0x20
#define LIS3DH_REG_CTRL2 0x21
#define LIS3DH_REG_CTRL3 0x22
#define LIS3DH_REG_CTRL4 0x23
#define LIS3DH_REG_CTRL5 0x24
#define LIS3DH_REG_CTRL6 0x25
#define LIS3DH_REG_STATUS2 0x27
#define LIS3DH_REG_OUT_X_L 0x28 /**< X-axis acceleration data. Low value */
#define LIS3DH_LSB16_TO_KILO_LSB10 6400

View file

@ -0,0 +1,12 @@
# Adafruit PyCamera Library [![Build Status](https://github.com/adafruit/Adafruit_PyCamera/workflows/Arduino%20Library%20CI/badge.svg)](https://github.com/adafruit/Adafruit_PyCamera/actions) [![Documentation](https://github.com/adafruit/ci-arduino/blob/master/assets/doxygen_badge.svg)](http://adafruit.github.io/Adafruit_PyCamera/html/index.html)
This is a library for the Adafruit MEMENTO:
* [https://www.adafruit.com/products/5420](https://www.adafruit.com/product/5420)
Adafruit invests time and resources providing this open source code, please support Adafruit and open-source hardware by purchasing products from Adafruit!
Written by ladyada for Adafruit Industries.
MIT license, check license.txt for more information All text above must be included in any redistribution
To install, use the Arduino Library Manager and search for "Adafruit PyCamera" and install the library.

View file

@ -0,0 +1,742 @@
/*
TJpg_Decoder.cpp
Created by Bodmer 18/10/19
Latest version here:
https://github.com/Bodmer/TJpg_Decoder
*/
#include "TJpg_Decoder.h"
// Create a class instance to be used by the sketch (defined as extern in
// header)
TJpg_Decoder TJpgDec;
/**************************************************************************/
/**
* @brief Constructor for the TJpg_Decoder class.
*
* @details Initializes a new instance of the TJpg_Decoder class.
* Sets up a pointer to this class instance for static functions.
*/
/**************************************************************************/
TJpg_Decoder::TJpg_Decoder() {
// Setup a pointer to this class for static functions
thisPtr = this;
}
/**************************************************************************/
/**
* @brief Destructor for the TJpg_Decoder class.
*
* @details Releases any resources or memory allocated by the TJpg_Decoder
* instance.
*/
/**************************************************************************/
TJpg_Decoder::~TJpg_Decoder() {
// Bye
}
/**************************************************************************/
/**
* @brief Sets the byte swapping option for the JPEG decoder.
*
* @details This function configures whether the bytes in the decoded JPEG image
* should be swapped. This is useful for different hardware
* configurations and image rendering methods.
*
* @param swapBytes Boolean flag to enable or disable byte swapping.
*/
/**************************************************************************/
void TJpg_Decoder::setSwapBytes(bool swapBytes) { _swap = swapBytes; }
/**************************************************************************/
/**
* @brief Sets the JPEG image scale factor.
*
* @details This function configures the scaling factor for the JPEG decoding
* process. It allows the image to be reduced by a factor of 1, 2, 4, or 8. This
* can be useful for handling large images or for faster rendering with reduced
* resolution.
*
* @param scaleFactor The scale factor for the JPEG image (1, 2, 4, or 8).
*/
/**************************************************************************/
void TJpg_Decoder::setJpgScale(uint8_t scaleFactor) {
switch (scaleFactor) {
case 1:
jpgScale = 0;
break;
case 2:
jpgScale = 1;
break;
case 4:
jpgScale = 2;
break;
case 8:
jpgScale = 3;
break;
default:
jpgScale = 0;
}
}
/**************************************************************************/
/**
* @brief Sets the callback function for rendering decoded JPEG blocks.
*
* @details This function sets a user-defined callback function that is called
* during the JPEG decoding process. The callback function is
* responsible for rendering the decoded image blocks to the display or other
* output devices. This allows for custom handling of the JPEG decoding process.
*
* @param sketchCallback The callback function to be used for rendering decoded
* blocks.
*/
/**************************************************************************/
void TJpg_Decoder::setCallback(SketchCallback sketchCallback) {
tft_output = sketchCallback;
}
/**************************************************************************/
/**
* @brief Called by tjpgd.c to retrieve more data for JPEG decoding.
*
* @details This function is a callback used by the JPEG decoding library
* (tjpgd.c) to fetch more data for the decoding process. It handles data
* retrieval from various sources including arrays, SPIFFS, and SD files. The
* function ensures that the end of the data source is not exceeded and copies
* the required number of bytes into the provided buffer.
*
* @param jdec Pointer to the JDEC structure, representing the state of the JPEG
* decompression process.
* @param buf Pointer to the buffer where the fetched data should be stored. If
* null, no data is copied.
* @param len The number of bytes to fetch.
*
* @return The actual number of bytes fetched.
*/
/**************************************************************************/
unsigned int TJpg_Decoder::jd_input(JDEC *jdec, uint8_t *buf,
unsigned int len) {
TJpg_Decoder *thisPtr = TJpgDec.thisPtr;
jdec = jdec; // Supress warning
// Handle an array input
if (thisPtr->jpg_source == TJPG_ARRAY) {
// Avoid running off end of array
if (thisPtr->array_index + len > thisPtr->array_size) {
len = thisPtr->array_size - thisPtr->array_index;
}
// If buf is valid then copy len bytes to buffer
if (buf)
memcpy_P(buf,
(const uint8_t *)(thisPtr->array_data + thisPtr->array_index),
len);
// Move pointer
thisPtr->array_index += len;
}
#ifdef TJPGD_LOAD_FFS
// Handle SPIFFS input
else if (thisPtr->jpg_source == TJPG_FS_FILE) {
// Check how many bytes are available
uint32_t bytesLeft = thisPtr->jpgFile.available();
if (bytesLeft < len)
len = bytesLeft;
if (buf) {
// Read into buffer, pointer moved as well
thisPtr->jpgFile.read(buf, len);
} else {
// Buffer is null, so skip data by moving pointer
thisPtr->jpgFile.seek(thisPtr->jpgFile.position() + len);
}
}
#endif
#if defined(TJPGD_LOAD_SD_LIBRARY)
// Handle SD library input
else if (thisPtr->jpg_source == TJPG_SD_FILE) {
// Check how many bytes are available
uint32_t bytesLeft = thisPtr->jpgSdFile.available();
if (bytesLeft < len)
len = bytesLeft;
if (buf) {
// Read into buffer, pointer moved as well
thisPtr->jpgSdFile.read(buf, len);
} else {
// Buffer is null, so skip data by moving pointer
thisPtr->jpgSdFile.seek(thisPtr->jpgSdFile.position() + len);
}
}
#endif
return len;
}
/**************************************************************************/
/**
* @brief Called by tjpgd.c with an image block for rendering.
*
* @details This function is a callback used by the JPEG decoding library
* (tjpgd.c) to pass decoded image blocks for rendering. It may be a complete or
* partial Minimum Coded Unit (MCU). The function calculates the
* position and dimensions of the image block and passes these parameters along
* with the image data to a user-defined rendering function.
*
* @param jdec Pointer to the JDEC structure, representing the state of the JPEG
* decompression process.
* @param bitmap Pointer to the image block data.
* @param jrect Pointer to the JRECT structure defining the position and size of
* the image block.
*
* @return The return value from the user-defined rendering function.
*/
/**************************************************************************/
// Pass image block back to the sketch for rendering, may be a complete or
// partial MCU
int TJpg_Decoder::jd_output(JDEC *jdec, void *bitmap, JRECT *jrect) {
// This is a static function so create a pointer to access other members of
// the class
TJpg_Decoder *thisPtr = TJpgDec.thisPtr;
jdec = jdec; // Supress warning as ID is not used
// Retrieve rendering parameters and add any offset
int16_t x = jrect->left + thisPtr->jpeg_x;
int16_t y = jrect->top + thisPtr->jpeg_y;
uint16_t w = jrect->right + 1 - jrect->left;
uint16_t h = jrect->bottom + 1 - jrect->top;
// Pass the image block and rendering parameters in a callback to the sketch
return thisPtr->tft_output(x, y, w, h, (uint16_t *)bitmap);
}
#if defined(TJPGD_LOAD_SD_LIBRARY) || defined(TJPGD_LOAD_FFS)
************************************************************************** /
/**
* @brief Draw a named jpg file at x,y (name in char array).
* @details Generic file call for SD or SPIFFS, uses leading / to
* distinguish SPIFFS files.
* @param x X-coordinate where the image will be drawn.
* @param y Y-coordinate where the image will be drawn.
* @param pFilename Pointer to the character array containing the file name.
* @return JRESULT status of the drawing operation.
*/
/**************************************************************************/
// Generic file call for SD or SPIFFS, uses leading / to distinguish SPIFFS
// files
JRESULT TJpg_Decoder::drawJpg(int32_t x, int32_t y, const char *pFilename) {
#if defined(ARDUINO_ARCH_ESP8266) || defined(ESP32)
#if defined(TJPGD_LOAD_SD_LIBRARY)
if (*pFilename == '/')
#endif
return drawFsJpg(x, y, pFilename);
#endif
#if defined(TJPGD_LOAD_SD_LIBRARY)
return drawSdJpg(x, y, pFilename);
#endif
return JDR_INP;
}
/**************************************************************************/
/**
* @brief Draw a named jpg file at x,y (name in String).
* @details Generic file call for SD or SPIFFS, uses leading / to distinguish
* SPIFFS files.
* @param x X-coordinate where the image will be drawn.
* @param y Y-coordinate where the image will be drawn.
* @param pFilename String containing the file name.
* @return JRESULT status of the drawing operation.
*/
/**************************************************************************/
// Generic file call for SD or SPIFFS, uses leading / to distinguish SPIFFS
// files
JRESULT TJpg_Decoder::drawJpg(int32_t x, int32_t y, const String &pFilename) {
#if defined(ARDUINO_ARCH_ESP8266) || defined(ESP32)
#if defined(TJPGD_LOAD_SD_LIBRARY)
if (pFilename.charAt(0) == '/')
#endif
return drawFsJpg(x, y, pFilename);
#endif
#if defined(TJPGD_LOAD_SD_LIBRARY)
return drawSdJpg(x, y, pFilename);
#endif
return JDR_INP;
}
/**************************************************************************/
/**
* @brief Get width and height of a jpg file (name in char array).
* @details Generic file call for SD or SPIFFS, uses leading / to distinguish
* SPIFFS files.
* @param w Pointer to store the width of the image.
* @param h Pointer to store the height of the image.
* @param pFilename Pointer to the character array containing the file name.
* @return JRESULT status of the size retrieval operation.
*/
/**************************************************************************/
// Generic file call for SD or SPIFFS, uses leading / to distinguish SPIFFS
// files
JRESULT TJpg_Decoder::getJpgSize(uint16_t *w, uint16_t *h,
const char *pFilename) {
#if defined(ARDUINO_ARCH_ESP8266) || defined(ESP32)
#if defined(TJPGD_LOAD_SD_LIBRARY)
if (*pFilename == '/')
#endif
return getFsJpgSize(w, h, pFilename);
#endif
#if defined(TJPGD_LOAD_SD_LIBRARY)
return getSdJpgSize(w, h, pFilename);
#endif
return JDR_INP;
}
/**************************************************************************/
/**
* @brief Get width and height of a jpg file (name in String).
* @details Generic file call for SD or SPIFFS, uses leading / to distinguish
* SPIFFS files.
* @param w Pointer to store the width of the image.
* @param h Pointer to store the height of the image.
* @param pFilename String containing the file name.
* @return JRESULT status of the size retrieval operation.
*/
/**************************************************************************/
// Generic file call for SD or SPIFFS, uses leading / to distinguish SPIFFS
// files
JRESULT TJpg_Decoder::getJpgSize(uint16_t *w, uint16_t *h,
const String &pFilename) {
#if defined(ARDUINO_ARCH_ESP8266) || defined(ESP32)
#if defined(TJPGD_LOAD_SD_LIBRARY)
if (pFilename.charAt(0) == '/')
#endif
return getFsJpgSize(w, h, pFilename);
#endif
#if defined(TJPGD_LOAD_SD_LIBRARY)
return getSdJpgSize(w, h, pFilename);
#endif
return JDR_INP;
}
#endif
#ifdef TJPGD_LOAD_FFS
/**************************************************************************/
/**
* @brief Draw a named jpg file at x,y (name in char array) from SPIFFS or
* LittleFS.
* @param x X-coordinate where the image will be drawn.
* @param y Y-coordinate where the image will be drawn.
* @param pFilename Pointer to the character array containing the file name.
* @param fs Filesystem reference (SPIFFS or LittleFS).
* @return JRESULT status of the drawing operation.
*/
/**************************************************************************/
// Call specific to SPIFFS
JRESULT TJpg_Decoder::drawFsJpg(int32_t x, int32_t y, const char *pFilename,
fs::FS &fs) {
// Check if file exists
if (!fs.exists(pFilename)) {
Serial.println(F("Jpeg file not found"));
return JDR_INP;
}
return drawFsJpg(x, y, fs.open(pFilename, "r"));
}
/**************************************************************************/
/**
* @brief Draw a named jpg file at x,y (name in String) from SPIFFS or LittleFS.
* @param x X-coordinate where the image will be drawn.
* @param y Y-coordinate where the image will be drawn.
* @param pFilename String containing the file name.
* @param fs Filesystem reference (SPIFFS or LittleFS).
* @return JRESULT status of the drawing operation.
*/
/**************************************************************************/
JRESULT TJpg_Decoder::drawFsJpg(int32_t x, int32_t y, const String &pFilename,
fs::FS &fs) {
// Check if file exists
if (!fs.exists(pFilename)) {
Serial.println(F("Jpeg file not found"));
return JDR_INP;
}
return drawFsJpg(x, y, fs.open(pFilename, "r"));
}
/**************************************************************************/
/**
* @brief Draw a jpg with opened file handle at x,y.
* @param x X-coordinate where the image will be drawn.
* @param y Y-coordinate where the image will be drawn.
* @param inFile Opened file handle to the jpg file.
* @return JRESULT status of the drawing operation.
*/
/**************************************************************************/
JRESULT TJpg_Decoder::drawFsJpg(int32_t x, int32_t y, fs::File inFile) {
JDEC jdec;
JRESULT jresult = JDR_OK;
jpg_source = TJPG_FS_FILE;
jpeg_x = x;
jpeg_y = y;
jdec.swap = _swap;
jpgFile = inFile;
jresult = jd_prepare(&jdec, jd_input, workspace, TJPGD_WORKSPACE_SIZE,
(unsigned int)0);
// Extract image and render
if (jresult == JDR_OK) {
jresult = jd_decomp(&jdec, jd_output, jpgScale);
}
// Close file
if (jpgFile)
jpgFile.close();
return jresult;
}
/**************************************************************************/
/**
* @brief Get width and height of a jpg saved in SPIFFS or LittleFS (name in
* char array).
* @param w Pointer to store the width of the image.
* @param h Pointer to store the height of the image.
* @param pFilename Pointer to the character array containing the file name.
* @param fs Filesystem reference (SPIFFS or LittleFS).
* @return JRESULT status of the size retrieval operation.
*/
/**************************************************************************/
// Call specific to SPIFFS
JRESULT TJpg_Decoder::getFsJpgSize(uint16_t *w, uint16_t *h,
const char *pFilename, fs::FS &fs) {
// Check if file exists
if (!fs.exists(pFilename)) {
Serial.println(F("Jpeg file not found"));
return JDR_INP;
}
return getFsJpgSize(w, h, fs.open(pFilename, "r"));
}
/**************************************************************************/
/**
* @brief Get width and height of a jpg saved in SPIFFS or LittleFS (name in
* String).
* @param w Pointer to store the width of the image.
* @param h Pointer to store the height of the image.
* @param pFilename String containing the file name.
* @param fs Filesystem reference (SPIFFS or LittleFS).
* @return JRESULT status of the size retrieval operation.
*/
/**************************************************************************/
JRESULT TJpg_Decoder::getFsJpgSize(uint16_t *w, uint16_t *h,
const String &pFilename, fs::FS &fs) {
// Check if file exists
if (!fs.exists(pFilename)) {
Serial.println(F("Jpeg file not found"));
return JDR_INP;
}
return getFsJpgSize(w, h, fs.open(pFilename, "r"));
}
/**************************************************************************/
/**
* @brief Get width and height of a jpg saved in SPIFFS.
* @details Retrieves the dimensions of a JPEG image stored in SPIFFS.
* @param w Pointer to store the width of the image.
* @param h Pointer to store the height of the image.
* @param inFile Opened file handle to the jpg file.
* @return JRESULT status of the size retrieval operation.
*/
/**************************************************************************/
JRESULT TJpg_Decoder::getFsJpgSize(uint16_t *w, uint16_t *h, fs::File inFile) {
JDEC jdec;
JRESULT jresult = JDR_OK;
*w = 0;
*h = 0;
jpg_source = TJPG_FS_FILE;
jpgFile = inFile;
jresult = jd_prepare(&jdec, jd_input, workspace, TJPGD_WORKSPACE_SIZE, 0);
if (jresult == JDR_OK) {
*w = jdec.width;
*h = jdec.height;
}
// Close file
if (jpgFile)
jpgFile.close();
return jresult;
}
#endif
#if defined(TJPGD_LOAD_SD_LIBRARY)
/**************************************************************************/
/**
* @brief Draw a named jpg SD file at x,y (name in char array).
* @details Draws a JPEG image from an SD card at specified coordinates.
* @param x X-coordinate where the image will be drawn.
* @param y Y-coordinate where the image will be drawn.
* @param pFilename Pointer to the character array containing the file name.
* @return JRESULT status of the drawing operation.
*/
/**************************************************************************/
// Call specific to SD
JRESULT TJpg_Decoder::drawSdJpg(int32_t x, int32_t y, const char *pFilename) {
// Check if file exists
if (!SD.exists(pFilename)) {
Serial.println(F("Jpeg file not found"));
return JDR_INP;
}
return drawSdJpg(x, y, SD.open(pFilename, FILE_READ));
}
/**************************************************************************/
/**
* @brief Draw a named jpg SD file at x,y (name in String).
* @details Draws a JPEG image from an SD card at specified coordinates.
* @param x X-coordinate where the image will be drawn.
* @param y Y-coordinate where the image will be drawn.
* @param pFilename String containing the file name.
* @return JRESULT status of the drawing operation.
*/
/**************************************************************************/
JRESULT TJpg_Decoder::drawSdJpg(int32_t x, int32_t y, const String &pFilename) {
// Check if file exists
if (!SD.exists(pFilename)) {
Serial.println(F("Jpeg file not found"));
return JDR_INP;
}
return drawSdJpg(x, y, SD.open(pFilename, FILE_READ));
}
/**************************************************************************/
/**
* @brief Draw a jpg with opened SD file handle at x,y.
* @details Renders a JPEG image from an opened SD file at specified
* coordinates.
* @param x X-coordinate where the image will be drawn.
* @param y Y-coordinate where the image will be drawn.
* @param inFile Opened file handle to the jpg file.
* @return JRESULT status of the drawing operation.
*/
/**************************************************************************/
JRESULT TJpg_Decoder::drawSdJpg(int32_t x, int32_t y, File inFile) {
JDEC jdec;
JRESULT jresult = JDR_OK;
jpg_source = TJPG_SD_FILE;
jpeg_x = x;
jpeg_y = y;
jdec.swap = _swap;
jpgSdFile = inFile;
jresult = jd_prepare(&jdec, jd_input, workspace, TJPGD_WORKSPACE_SIZE, 0);
// Extract image and render
if (jresult == JDR_OK) {
jresult = jd_decomp(&jdec, jd_output, jpgScale);
}
// Close file
if (jpgSdFile)
jpgSdFile.close();
return jresult;
}
/**************************************************************************/
/**
* @brief Get width and height of a jpg saved in SPIFFS.
* @details Retrieves the dimensions of a JPEG image stored in SPIFFS.
* @param w Pointer to store the width of the image.
* @param h Pointer to store the height of the image.
* @param pFilename Pointer to the character array containing the file name.
* @return JRESULT status of the size retrieval operation.
*/
/**************************************************************************/
// Call specific to SD
JRESULT TJpg_Decoder::getSdJpgSize(uint16_t *w, uint16_t *h,
const char *pFilename) {
// Check if file exists
if (!SD.exists(pFilename)) {
Serial.println(F("Jpeg file not found"));
return JDR_INP;
}
return getSdJpgSize(w, h, SD.open(pFilename, FILE_READ));
}
/**************************************************************************/
/**
* @brief Get width and height of a jpg saved in SPIFFS.
* @details Retrieves the dimensions of a JPEG image stored in SPIFFS.
* @param w Pointer to store the width of the image.
* @param h Pointer to store the height of the image.
* @param pFilename String containing the file name.
* @return JRESULT status of the size retrieval operation.
*/
/**************************************************************************/
JRESULT TJpg_Decoder::getSdJpgSize(uint16_t *w, uint16_t *h,
const String &pFilename) {
// Check if file exists
if (!SD.exists(pFilename)) {
Serial.println(F("Jpeg file not found"));
return JDR_INP;
}
return getSdJpgSize(w, h, SD.open(pFilename, FILE_READ));
}
/**************************************************************************/
/**
* @brief Get width and height of a jpg saved in SPIFFS.
* @details Retrieves the dimensions of a JPEG image stored in SPIFFS.
* @param w Pointer to store the width of the image.
* @param h Pointer to store the height of the image.
* @param inFile Opened file handle to the jpg file.
* @return JRESULT status of the size retrieval operation.
*/
/**************************************************************************/
JRESULT TJpg_Decoder::getSdJpgSize(uint16_t *w, uint16_t *h, File inFile) {
JDEC jdec;
JRESULT jresult = JDR_OK;
*w = 0;
*h = 0;
jpg_source = TJPG_SD_FILE;
jpgSdFile = inFile;
jresult = jd_prepare(&jdec, jd_input, workspace, TJPGD_WORKSPACE_SIZE, 0);
if (jresult == JDR_OK) {
*w = jdec.width;
*h = jdec.height;
}
// Close file
if (jpgSdFile)
jpgSdFile.close();
return jresult;
}
#endif
/**************************************************************************/
/**
* @brief Draw a jpg saved in a FLASH memory array.
* @details Renders a JPEG image stored in a FLASH memory array at specified
* coordinates.
* @param x X-coordinate where the image will be drawn.
* @param y Y-coordinate where the image will be drawn.
* @param jpeg_data Pointer to the JPEG data in FLASH memory.
* @param data_size Size of the JPEG data in bytes.
* @return JRESULT status of the drawing operation.
*/
/**************************************************************************/
JRESULT TJpg_Decoder::drawJpg(int32_t x, int32_t y, const uint8_t jpeg_data[],
uint32_t data_size) {
JDEC jdec;
JRESULT jresult = JDR_OK;
jpg_source = TJPG_ARRAY;
array_index = 0;
array_data = jpeg_data;
array_size = data_size;
jpeg_x = x;
jpeg_y = y;
jdec.swap = _swap;
// Analyse input data
jresult = jd_prepare(&jdec, jd_input, workspace, TJPGD_WORKSPACE_SIZE, 0);
// Extract image and render
if (jresult == JDR_OK) {
jresult = jd_decomp(&jdec, jd_output, jpgScale);
}
return jresult;
}
/**************************************************************************/
/**
* @brief Get width and height of a jpg saved in a FLASH memory array.
* @details Retrieves the dimensions of a JPEG image stored in a FLASH memory
* array.
* @param w Pointer to store the width of the image.
* @param h Pointer to store the height of the image.
* @param jpeg_data Pointer to the JPEG data in FLASH memory.
* @param data_size Size of the JPEG data in bytes.
* @return JRESULT status of the size retrieval operation.
*/
/**************************************************************************/
JRESULT TJpg_Decoder::getJpgSize(uint16_t *w, uint16_t *h,
const uint8_t jpeg_data[],
uint32_t data_size) {
JDEC jdec;
JRESULT jresult = JDR_OK;
*w = 0;
*h = 0;
jpg_source = TJPG_ARRAY;
array_index = 0;
array_data = jpeg_data;
array_size = data_size;
// Analyse input data
jresult = jd_prepare(&jdec, jd_input, workspace, TJPGD_WORKSPACE_SIZE, 0);
if (jresult == JDR_OK) {
*w = jdec.width;
*h = jdec.height;
}
return jresult;
}

View file

@ -0,0 +1,135 @@
/*
TJpg_Decoder.h
JPEG Decoder for Arduino using TJpgDec:
http://elm-chan.org/fsw/tjpgd/00index.html
Incorporated into an Arduino library by Bodmer 18/10/19
Latest version here:
https://github.com/Bodmer/TJpg_Decoder
*/
#ifndef TJpg_Decoder_H
#define TJpg_Decoder_H
#include "Arduino.h"
#include "User_Config.h"
#include "tjpgd.h"
#if defined(TJPGD_LOAD_SD_LIBRARY)
#include <SD.h>
#endif
enum { TJPG_ARRAY = 0, TJPG_FS_FILE, TJPG_SD_FILE };
//------------------------------------------------------------------------------
typedef bool (*SketchCallback)(int16_t x, int16_t y, uint16_t w, uint16_t h,
uint16_t *data);
/**************************************************************************/
/**
* @class TJpg_Decoder
* @brief JPEG Decoder for Arduino using TJpgDec.
*
* Incorporates the TJpgDec library into an Arduino library for JPEG decoding.
* Supports loading JPEG files from various sources like SD card, SPIFFS, and
* memory arrays.
*/
/**************************************************************************/
class TJpg_Decoder {
private:
#if defined(TJPGD_LOAD_SD_LIBRARY)
File jpgSdFile; ///< File handle for JPEG files on SD card.
#endif
#ifdef TJPGD_LOAD_FFS
fs::File jpgFile; ///< File handle for JPEG files in SPIFFS.
#endif
public:
TJpg_Decoder(); ///< Constructor for TJpg_Decoder.
~TJpg_Decoder(); ///< Destructor for TJpg_Decoder.
static int
jd_output(JDEC *jdec, void *bitmap,
JRECT *jrect); ///< Static callback for outputting JPEG blocks.
static unsigned int
jd_input(JDEC *jdec, uint8_t *buf,
unsigned int len); ///< Static callback for inputting JPEG data.
void setJpgScale(uint8_t scale); ///< Set the JPEG scaling factor.
void
setCallback(SketchCallback sketchCallback); ///< Set the callback function for
///< rendering decoded blocks.
#if defined(TJPGD_LOAD_SD_LIBRARY) || defined(TJPGD_LOAD_FFS)
JRESULT drawJpg(int32_t x, int32_t y, const char *pFilename);
JRESULT drawJpg(int32_t x, int32_t y, const String &pFilename);
JRESULT getJpgSize(uint16_t *w, uint16_t *h, const char *pFilename);
JRESULT getJpgSize(uint16_t *w, uint16_t *h, const String &pFilename);
#endif
#if defined(TJPGD_LOAD_SD_LIBRARY)
JRESULT drawSdJpg(int32_t x, int32_t y, const char *pFilename);
JRESULT drawSdJpg(int32_t x, int32_t y, const String &pFilename);
JRESULT drawSdJpg(int32_t x, int32_t y, File inFile);
JRESULT getSdJpgSize(uint16_t *w, uint16_t *h, const char *pFilename);
JRESULT getSdJpgSize(uint16_t *w, uint16_t *h, const String &pFilename);
JRESULT getSdJpgSize(uint16_t *w, uint16_t *h, File inFile);
#endif
#ifdef TJPGD_LOAD_FFS
JRESULT drawFsJpg(int32_t x, int32_t y, const char *pFilename,
fs::FS &fs = SPIFFS);
JRESULT drawFsJpg(int32_t x, int32_t y, const String &pFilename,
fs::FS &fs = SPIFFS);
JRESULT drawFsJpg(int32_t x, int32_t y, fs::File inFile);
JRESULT getFsJpgSize(uint16_t *w, uint16_t *h, const char *pFilename,
fs::FS &fs = SPIFFS);
JRESULT getFsJpgSize(uint16_t *w, uint16_t *h, const String &pFilename,
fs::FS &fs = SPIFFS);
JRESULT getFsJpgSize(uint16_t *w, uint16_t *h, fs::File inFile);
#endif
JRESULT drawJpg(int32_t x, int32_t y, const uint8_t array[],
uint32_t array_size);
JRESULT getJpgSize(uint16_t *w, uint16_t *h, const uint8_t array[],
uint32_t array_size);
void setSwapBytes(bool swap);
bool _swap = false; ///< Swap byte order flag.
const uint8_t *array_data =
nullptr; ///< Pointer to JPEG data in memory array.
uint32_t array_index = 0; ///< Current index in the memory array.
uint32_t array_size = 0; ///< Size of the memory array.
/*! \cond DOXYGEN_SHOULD_SKIP_THIS */
uint8_t workspace[TJPGD_WORKSPACE_SIZE] __attribute__((
aligned(4))); ///< Workspace for TJpgDec, aligned to 32-bit boundary.
/*! \endcond */
uint8_t jpg_source = 0; ///< Source of the JPEG data.
int16_t jpeg_x = 0; ///< X-coordinate for rendering JPEG.
int16_t jpeg_y = 0; ///< Y-coordinate for rendering JPEG.
uint8_t jpgScale = 0; ///< JPEG scaling factor.
SketchCallback tft_output =
nullptr; ///< Callback function for rendering JPEG blocks.
TJpg_Decoder *thisPtr =
nullptr; ///< Pointer to this instance, used in static functions.
};
extern TJpg_Decoder TJpgDec; ///< Global instance of TJpg_Decoder.
#endif // TJpg_Decoder_H

View file

@ -0,0 +1,127 @@
# Adafruit Community Code of Conduct
## Our Pledge
In the interest of fostering an open and welcoming environment, we as
contributors and leaders pledge to making participation in our project and
our community a harassment-free experience for everyone, regardless of age, body
size, disability, ethnicity, gender identity and expression, level or type of
experience, education, socio-economic status, nationality, personal appearance,
race, religion, or sexual identity and orientation.
## Our Standards
We are committed to providing a friendly, safe and welcoming environment for
all.
Examples of behavior that contributes to creating a positive environment
include:
* Be kind and courteous to others
* Using welcoming and inclusive language
* Being respectful of differing viewpoints and experiences
* Collaborating with other community members
* Gracefully accepting constructive criticism
* Focusing on what is best for the community
* Showing empathy towards other community members
Examples of unacceptable behavior by participants include:
* The use of sexualized language or imagery and sexual attention or advances
* The use of inappropriate images, including in a community member's avatar
* The use of inappropriate language, including in a community member's nickname
* Any spamming, flaming, baiting or other attention-stealing behavior
* Excessive or unwelcome helping; answering outside the scope of the question
asked
* Trolling, insulting/derogatory comments, and personal or political attacks
* Public or private harassment
* Publishing others' private information, such as a physical or electronic
address, without explicit permission
* Other conduct which could reasonably be considered inappropriate
The goal of the standards and moderation guidelines outlined here is to build
and maintain a respectful community. We ask that you dont just aim to be
"technically unimpeachable", but rather try to be your best self.
We value many things beyond technical expertise, including collaboration and
supporting others within our community. Providing a positive experience for
other community members can have a much more significant impact than simply
providing the correct answer.
## Our Responsibilities
Project leaders are responsible for clarifying the standards of acceptable
behavior and are expected to take appropriate and fair corrective action in
response to any instances of unacceptable behavior.
Project leaders have the right and responsibility to remove, edit, or
reject messages, comments, commits, code, issues, and other contributions
that are not aligned to this Code of Conduct, or to ban temporarily or
permanently any community member for other behaviors that they deem
inappropriate, threatening, offensive, or harmful.
## Moderation
Instances of behaviors that violate the Adafruit Community Code of Conduct
may be reported by any member of the community. Community members are
encouraged to report these situations, including situations they witness
involving other community members.
You may report in the following ways:
In any situation, you may send an email to <support@adafruit.com>.
On the Adafruit Discord, you may send an open message from any channel
to all Community Helpers by tagging @community helpers. You may also send an
open message from any channel, or a direct message to @kattni#1507,
@tannewt#4653, @Dan Halbert#1614, @cater#2442, @sommersoft#0222, or
@Andon#8175.
Email and direct message reports will be kept confidential.
In situations on Discord where the issue is particularly egregious, possibly
illegal, requires immediate action, or violates the Discord terms of service,
you should also report the message directly to Discord.
These are the steps for upholding our communitys standards of conduct.
1. Any member of the community may report any situation that violates the
Adafruit Community Code of Conduct. All reports will be reviewed and
investigated.
2. If the behavior is an egregious violation, the community member who
committed the violation may be banned immediately, without warning.
3. Otherwise, moderators will first respond to such behavior with a warning.
4. Moderators follow a soft "three strikes" policy - the community member may
be given another chance, if they are receptive to the warning and change their
behavior.
5. If the community member is unreceptive or unreasonable when warned by a
moderator, or the warning goes unheeded, they may be banned for a first or
second offense. Repeated offenses will result in the community member being
banned.
## Scope
This Code of Conduct and the enforcement policies listed above apply to all
Adafruit Community venues. This includes but is not limited to any community
spaces (both public and private), the entire Adafruit Discord server, and
Adafruit GitHub repositories. Examples of Adafruit Community spaces include
but are not limited to meet-ups, audio chats on the Adafruit Discord, or
interaction at a conference.
This Code of Conduct applies both within project spaces and in public spaces
when an individual is representing the project or its community. As a community
member, you are representing our community, and are expected to behave
accordingly.
## Attribution
This Code of Conduct is adapted from the [Contributor Covenant][homepage],
version 1.4, available at
<https://www.contributor-covenant.org/version/1/4/code-of-conduct.html>,
and the [Rust Code of Conduct](https://www.rust-lang.org/en-US/conduct.html).
For other projects adopting the Adafruit Community Code of
Conduct, please contact the maintainers of those projects for enforcement.
If you wish to use this code of conduct for your own project, consider
explicitly mentioning your moderation policy or making a copy with your
own moderation policy so as to avoid confusion.

View file

@ -0,0 +1,208 @@
// SPDX-FileCopyrightText: 2023 Limor Fried for Adafruit Industries
//
// SPDX-License-Identifier: MIT
#include "Adafruit_PyCamera.h"
#include <Arduino.h>
Adafruit_PyCamera pycamera;
framesize_t validSizes[] = {FRAMESIZE_QQVGA, FRAMESIZE_QVGA, FRAMESIZE_HVGA,
FRAMESIZE_VGA, FRAMESIZE_SVGA, FRAMESIZE_XGA,
FRAMESIZE_HD, FRAMESIZE_SXGA, FRAMESIZE_UXGA,
FRAMESIZE_QXGA, FRAMESIZE_QSXGA};
// A colection of possible ring light colors
uint32_t ringlightcolors_RGBW[] = {0x00000000, 0x00FF0000, 0x00FFFF00,
0x0000FF00, 0x0000FFFF, 0x000000FF,
0x00FF00FF, 0xFF000000};
uint8_t ringlight_i = 0;
uint8_t ringlightBrightness = 100;
#define IRQ 3
void setup() {
Serial.begin(115200);
while (!Serial) yield();
delay(100);
if (!pycamera.begin()) {
Serial.println("Failed to initialize pyCamera interface");
while (1)
yield();
}
Serial.println("pyCamera hardware initialized!");
pinMode(IRQ, INPUT_PULLUP);
attachInterrupt(
IRQ, [] { Serial.println("IRQ!"); }, FALLING);
}
void loop() {
static uint8_t loopn = 0;
pycamera.setNeopixel(pycamera.Wheel(loopn));
loopn += 8;
pycamera.readButtons();
// Serial.printf("Buttons: 0x%08X\n\r", pycamera.readButtons());
// pycamera.timestamp();
pycamera.captureFrame();
// once the frame is captured we can draw ontot he framebuffer
if (pycamera.justPressed(AWEXP_SD_DET)) {
Serial.println(F("SD Card removed"));
pycamera.endSD();
pycamera.fb->setCursor(0, 32);
pycamera.fb->setTextSize(2);
pycamera.fb->setTextColor(pycamera.color565(255, 0, 0));
pycamera.fb->print(F("SD Card removed"));
delay(200);
}
if (pycamera.justReleased(AWEXP_SD_DET)) {
Serial.println(F("SD Card inserted!"));
pycamera.initSD();
pycamera.fb->setCursor(0, 32);
pycamera.fb->setTextSize(2);
pycamera.fb->setTextColor(pycamera.color565(255, 0, 0));
pycamera.fb->print(F("SD Card inserted"));
delay(200);
}
float A0_voltage = analogRead(A0) / 4096.0 * 3.3;
if (loopn == 0) {
Serial.printf("A0 = %0.1f V, Battery = %0.1f V\n\r", A0_voltage,
pycamera.readBatteryVoltage());
}
pycamera.fb->setCursor(0, 0);
pycamera.fb->setTextSize(2);
pycamera.fb->setTextColor(pycamera.color565(255, 255, 255));
pycamera.fb->print("A0 = ");
pycamera.fb->print(A0_voltage, 1);
pycamera.fb->print("V\nBattery = ");
pycamera.fb->print(pycamera.readBatteryVoltage(), 1);
pycamera.fb->print(" V");
// print the camera frame size
pycamera.fb->setCursor(0, 200);
pycamera.fb->setTextSize(2);
pycamera.fb->setTextColor(pycamera.color565(255, 255, 255));
pycamera.fb->print("Size:");
switch (pycamera.photoSize) {
case FRAMESIZE_QQVGA:
pycamera.fb->print("160x120");
break;
case FRAMESIZE_QVGA:
pycamera.fb->print("320x240");
break;
case FRAMESIZE_HVGA:
pycamera.fb->print("480x320");
break;
case FRAMESIZE_VGA:
pycamera.fb->print("640x480");
break;
case FRAMESIZE_SVGA:
pycamera.fb->print("800x600");
break;
case FRAMESIZE_XGA:
pycamera.fb->print("1024x768");
break;
case FRAMESIZE_HD:
pycamera.fb->print("1280x720");
break;
case FRAMESIZE_SXGA:
pycamera.fb->print("1280x1024");
break;
case FRAMESIZE_UXGA:
pycamera.fb->print("1600x1200");
break;
case FRAMESIZE_QXGA:
pycamera.fb->print("2048x1536");
break;
case FRAMESIZE_QSXGA:
pycamera.fb->print("2560x1920");
break;
default:
pycamera.fb->print("Unknown");
break;
}
float x_ms2, y_ms2, z_ms2;
if (pycamera.readAccelData(&x_ms2, &y_ms2, &z_ms2)) {
// Serial.printf("X=%0.2f, Y=%0.2f, Z=%0.2f\n\r", x_ms2, y_ms2, z_ms2);
pycamera.fb->setCursor(0, 220);
pycamera.fb->setTextSize(2);
pycamera.fb->setTextColor(pycamera.color565(255, 255, 255));
pycamera.fb->print("3D: ");
pycamera.fb->print(x_ms2, 1);
pycamera.fb->print(", ");
pycamera.fb->print(y_ms2, 1);
pycamera.fb->print(", ");
pycamera.fb->print(z_ms2, 1);
}
pycamera.blitFrame();
if (pycamera.justPressed(AWEXP_BUTTON_UP)) {
Serial.println("Up!");
for (int i = 0; i < sizeof(validSizes) / sizeof(framesize_t) - 1; ++i) {
if (pycamera.photoSize == validSizes[i]) {
pycamera.photoSize = validSizes[i + 1];
break;
}
}
}
if (pycamera.justPressed(AWEXP_BUTTON_DOWN)) {
Serial.println("Down!");
for (int i = sizeof(validSizes) / sizeof(framesize_t) - 1; i > 0; --i) {
if (pycamera.photoSize == validSizes[i]) {
pycamera.photoSize = validSizes[i - 1];
break;
}
}
}
if (pycamera.justPressed(AWEXP_BUTTON_RIGHT)) {
pycamera.specialEffect = (pycamera.specialEffect + 1) % 7;
pycamera.setSpecialEffect(pycamera.specialEffect);
Serial.printf("set effect: %d\n\r", pycamera.specialEffect);
}
if (pycamera.justPressed(AWEXP_BUTTON_LEFT)) {
pycamera.specialEffect = (pycamera.specialEffect + 6) % 7;
pycamera.setSpecialEffect(pycamera.specialEffect);
Serial.printf("set effect: %d\n\r", pycamera.specialEffect);
}
if (pycamera.justPressed(AWEXP_BUTTON_OK)) {
// iterate through all the ring light colors
ringlight_i =
(ringlight_i + 1) % (sizeof(ringlightcolors_RGBW) / sizeof(uint32_t));
pycamera.setRing(ringlightcolors_RGBW[ringlight_i]);
Serial.printf("set ringlight: 0x%08X\n\r",
(unsigned int)ringlightcolors_RGBW[ringlight_i]);
}
if (pycamera.justPressed(AWEXP_BUTTON_SEL)) {
// iterate through brightness levels, incrementing 25 at a time
if (ringlightBrightness >= 250)
ringlightBrightness = 0;
else
ringlightBrightness += 50;
pycamera.ring.setBrightness(ringlightBrightness);
pycamera.setRing(ringlightcolors_RGBW[ringlight_i]);
Serial.printf("set ringlight brightness: %d\n\r", ringlightBrightness);
}
if (pycamera.justPressed(SHUTTER_BUTTON)) {
Serial.println("Snap!");
if (pycamera.takePhoto("IMAGE", pycamera.photoSize)) {
pycamera.fb->setCursor(120, 100);
pycamera.fb->setTextSize(2);
pycamera.fb->setTextColor(pycamera.color565(255, 255, 255));
pycamera.fb->print("Snap!");
pycamera.speaker_tone(100, 50); // tone1 - B5
// pycamera.blitFrame();
}
}
delay(100);
}

View file

@ -0,0 +1,176 @@
#include "Adafruit_PyCamera.h"
#include <Arduino.h>
Adafruit_PyCamera pycamera;
framesize_t validSizes[] = {FRAMESIZE_QQVGA, FRAMESIZE_QVGA, FRAMESIZE_HVGA,
FRAMESIZE_VGA, FRAMESIZE_SVGA, FRAMESIZE_XGA,
FRAMESIZE_HD, FRAMESIZE_SXGA, FRAMESIZE_UXGA,
FRAMESIZE_QXGA, FRAMESIZE_QSXGA};
void setup() {
Serial.begin(115200);
// while (!Serial) yield();
// delay(1000);
Serial.setDebugOutput(true);
Serial.println("Hello world");
if (!pycamera.begin()) {
Serial.println("Failed to initialize pyCamera interface");
while (1)
yield();
}
Serial.println("pyCamera hardware initialized!");
}
void loop() {
static uint8_t loopn = 0;
pycamera.setNeopixel(pycamera.Wheel(loopn));
loopn += 8;
pycamera.readButtons();
// Serial.printf("Buttons: 0x%08X\n\r", pycamera.readButtons());
// pycamera.timestamp();
pycamera.captureFrame();
// once the frame is captured we can draw ontot he framebuffer
if (pycamera.justPressed(AWEXP_SD_DET)) {
Serial.println(F("SD Card removed"));
pycamera.endSD();
pycamera.fb->setCursor(0, 32);
pycamera.fb->setTextSize(2);
pycamera.fb->setTextColor(pycamera.color565(255, 0, 0));
pycamera.fb->print(F("SD Card removed"));
delay(200);
}
if (pycamera.justReleased(AWEXP_SD_DET)) {
Serial.println(F("SD Card inserted!"));
pycamera.initSD();
pycamera.fb->setCursor(0, 32);
pycamera.fb->setTextSize(2);
pycamera.fb->setTextColor(pycamera.color565(255, 0, 0));
pycamera.fb->print(F("SD Card inserted"));
delay(200);
}
float A0_voltage = analogRead(A0) / 4096.0 * 3.3;
float A1_voltage = analogRead(A1) / 4096.0 * 3.3;
if (loopn == 0) {
Serial.printf("A0 = %0.1f V, A1 = %0.1f V, Battery = %0.1f V\n\r",
A0_voltage, A1_voltage, pycamera.readBatteryVoltage());
}
pycamera.fb->setCursor(0, 0);
pycamera.fb->setTextSize(2);
pycamera.fb->setTextColor(pycamera.color565(255, 255, 255));
pycamera.fb->print("A0 = ");
pycamera.fb->print(A0_voltage, 1);
pycamera.fb->print("V, A1 = ");
pycamera.fb->print(A1_voltage, 1);
pycamera.fb->print("V\nBattery = ");
pycamera.fb->print(pycamera.readBatteryVoltage(), 1);
pycamera.fb->print(" V");
// print the camera frame size
pycamera.fb->setCursor(0, 200);
pycamera.fb->setTextSize(2);
pycamera.fb->setTextColor(pycamera.color565(255, 255, 255));
pycamera.fb->print("Size:");
switch (pycamera.photoSize) {
case FRAMESIZE_QQVGA:
pycamera.fb->print("160x120");
break;
case FRAMESIZE_QVGA:
pycamera.fb->print("320x240");
break;
case FRAMESIZE_HVGA:
pycamera.fb->print("480x320");
break;
case FRAMESIZE_VGA:
pycamera.fb->print("640x480");
break;
case FRAMESIZE_SVGA:
pycamera.fb->print("800x600");
break;
case FRAMESIZE_XGA:
pycamera.fb->print("1024x768");
break;
case FRAMESIZE_HD:
pycamera.fb->print("1280x720");
break;
case FRAMESIZE_SXGA:
pycamera.fb->print("1280x1024");
break;
case FRAMESIZE_UXGA:
pycamera.fb->print("1600x1200");
break;
case FRAMESIZE_QXGA:
pycamera.fb->print("2048x1536");
break;
case FRAMESIZE_QSXGA:
pycamera.fb->print("2560x1920");
break;
default:
pycamera.fb->print("Unknown");
break;
}
float x_ms2, y_ms2, z_ms2;
if (pycamera.readAccelData(&x_ms2, &y_ms2, &z_ms2)) {
// Serial.printf("X=%0.2f, Y=%0.2f, Z=%0.2f\n\r", x_ms2, y_ms2, z_ms2);
pycamera.fb->setCursor(0, 220);
pycamera.fb->setTextSize(2);
pycamera.fb->setTextColor(pycamera.color565(255, 255, 255));
pycamera.fb->print("3D: ");
pycamera.fb->print(x_ms2, 1);
pycamera.fb->print(", ");
pycamera.fb->print(y_ms2, 1);
pycamera.fb->print(", ");
pycamera.fb->print(z_ms2, 1);
}
pycamera.blitFrame();
if (pycamera.justPressed(AWEXP_BUTTON_UP)) {
Serial.println("Up!");
for (int i = 0; i < sizeof(validSizes) / sizeof(framesize_t) - 1; ++i) {
if (pycamera.photoSize == validSizes[i]) {
pycamera.photoSize = validSizes[i + 1];
break;
}
}
}
if (pycamera.justPressed(AWEXP_BUTTON_DOWN)) {
Serial.println("Down!");
for (int i = sizeof(validSizes) / sizeof(framesize_t) - 1; i > 0; --i) {
if (pycamera.photoSize == validSizes[i]) {
pycamera.photoSize = validSizes[i - 1];
break;
}
}
}
if (pycamera.justPressed(AWEXP_BUTTON_RIGHT)) {
pycamera.specialEffect = (pycamera.specialEffect + 1) % 7;
pycamera.setSpecialEffect(pycamera.specialEffect);
Serial.printf("set effect: %d\n\r", pycamera.specialEffect);
}
if (pycamera.justPressed(AWEXP_BUTTON_LEFT)) {
pycamera.specialEffect = (pycamera.specialEffect + 6) % 7;
pycamera.setSpecialEffect(pycamera.specialEffect);
Serial.printf("set effect: %d\n\r", pycamera.specialEffect);
}
if (pycamera.justPressed(SHUTTER_BUTTON)) {
Serial.println("Snap!");
if (pycamera.takePhoto("IMAGE", pycamera.photoSize)) {
pycamera.fb->setCursor(120, 100);
pycamera.fb->setTextSize(2);
pycamera.fb->setTextColor(pycamera.color565(255, 255, 255));
pycamera.fb->print("Snap!");
pycamera.speaker_tone(100, 50); // tone1 - B5
// pycamera.blitFrame();
}
}
delay(100);
}

View file

@ -0,0 +1,10 @@
name=Adafruit PyCamera Library
version=1.0.5
author=Adafruit
maintainer=Adafruit <info@adafruit.com>
sentence=Arduino library for the MEMENTO ESP32-S3 camera
paragraph=Arduino library for the MEMENTO ESP32-S3 camera
category=Device Control
url=https://github.com/adafruit/Adafruit_PyCamera
architectures=esp32
depends=Adafruit BusIO, Adafruit NeoPixel, Adafruit ST7735 and ST7789 Library, Adafruit AW9523, SdFat - Adafruit Fork

View file

@ -0,0 +1,21 @@
MIT License
Copyright (c) 2023 Adafruit Industries
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all
copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
SOFTWARE.

View file

@ -0,0 +1,112 @@
/*----------------------------------------------------------------------------/
/ TJpgDec - Tiny JPEG Decompressor R0.03 include file (C)ChaN, 2021
/----------------------------------------------------------------------------*/
#ifndef DEF_TJPGDEC
#define DEF_TJPGDEC
#ifdef __cplusplus
extern "C" {
#endif
#include "tjpgdcnf.h"
#include <string.h>
#if defined(_WIN32) /* VC++ or some compiler without stdint.h */
typedef unsigned char uint8_t;
typedef unsigned short uint16_t;
typedef short int16_t;
typedef unsigned long uint32_t;
typedef long int32_t;
#else /* Embedded platform */
#include <stdint.h>
#endif
struct JDEC;
#if JD_FASTDECODE >= 1
typedef int16_t jd_yuv_t;
#else
typedef uint8_t jd_yuv_t;
#endif
/* Error code */
typedef enum {
JDR_OK = 0, /* 0: Succeeded */
JDR_INTR, /* 1: Interrupted by output function */
JDR_INP, /* 2: Device error or wrong termination of input stream */
JDR_MEM1, /* 3: Insufficient memory pool for the image */
JDR_MEM2, /* 4: Insufficient stream input buffer */
JDR_PAR, /* 5: Parameter error */
JDR_FMT1, /* 6: Data format error (may be broken data) */
JDR_FMT2, /* 7: Right format but not supported */
JDR_FMT3 /* 8: Not supported JPEG standard */
} JRESULT;
/**
* @struct JRECT
* @brief Rectangular region in the output image.
*/
typedef struct {
uint16_t left; /**< Left end of the rectangle */
uint16_t right; /**< Right end of the rectangle */
uint16_t top; /**< Top end of the rectangle */
uint16_t bottom; /**< Bottom end of the rectangle */
} JRECT;
/**
* @struct JDEC
* @brief Decompressor object structure.
*
* This structure holds all the state information for the JPEG decompression
* process.
*/
typedef struct JDEC {
size_t dctr; /**< Number of bytes available in the input buffer */
uint8_t *dptr; /**< Current data read pointer */
uint8_t *inbuf; /**< Bit stream input buffer */
uint8_t dbit; /**< Number of bits available in wreg or reading bit mask */
uint8_t scale; /**< Output scaling ratio */
uint8_t msx; /**< MCU size in units of blocks (width) */
uint8_t msy; /**< MCU size in units of blocks (height) */
uint8_t qtid[3]; /**< Quantization table ID of each component, Y, Cb, Cr */
uint8_t ncomp; /**< Number of color components 1:grayscale, 3:color */
int16_t dcv[3]; /**< Previous DC element of each component */
uint16_t nrst; /**< Restart interval */
uint16_t width; /**< Width of the input image in pixels */
uint16_t height; /**< Height of the input image in pixels */
uint8_t *huffbits[2][2]; /**< Huffman bit distribution tables [id][dcac] */
uint16_t *huffcode[2][2]; /**< Huffman code word tables [id][dcac] */
uint8_t *huffdata[2][2]; /**< Huffman decoded data tables [id][dcac] */
int32_t *qttbl[4]; /**< Dequantizer tables [id] */
#if JD_FASTDECODE >= 1
uint32_t wreg; /**< Working shift register */
uint8_t marker; /**< Detected marker (0:None) */
#if JD_FASTDECODE == 2
uint8_t longofs[2][2]; /**< Table offset of long code [id][dcac] */
uint16_t
*hufflut_ac[2]; /**< Fast huffman decode tables for AC short code [id] */
uint8_t
*hufflut_dc[2]; /**< Fast huffman decode tables for DC short code [id] */
#endif
#endif
void *workbuf; /**< Working buffer for IDCT and RGB output */
jd_yuv_t *mcubuf; /**< Working buffer for the MCU */
void *pool; /**< Pointer to available memory pool */
size_t sz_pool; /**< Size of memory pool (bytes available) */
size_t (*infunc)(struct JDEC *, uint8_t *,
size_t); /**< Pointer to jpeg stream input function */
void *device; /**< Pointer to I/O device identifier for the session */
uint8_t swap; /**< Byte swap flag added by Bodmer to control byte swapping */
} JDEC;
/* TJpgDec API functions */
JRESULT jd_prepare(JDEC *jd, size_t (*infunc)(JDEC *, uint8_t *, size_t),
void *pool, size_t sz_pool, void *dev);
JRESULT jd_decomp(JDEC *jd, int (*outfunc)(JDEC *, void *, JRECT *),
uint8_t scale);
#ifdef __cplusplus
}
#endif
#endif /* _TJPGDEC */

View file

@ -0,0 +1,44 @@
/*----------------------------------------------*/
/* TJpgDec System Configurations R0.03 */
/*----------------------------------------------*/
#define JD_SZBUF 512
/* Specifies size of stream input buffer */
#define JD_FORMAT 1
/* Specifies output pixel format.
/ 0: RGB888 (24-bit/pix)
/ 1: RGB565 (16-bit/pix)
/ 2: Grayscale (8-bit/pix)
*/
#define JD_USE_SCALE 1
/* Switches output descaling feature.
/ 0: Disable
/ 1: Enable
*/
#define JD_TBLCLIP 0
/* Use table conversion for saturation arithmetic. A bit faster, but increases 1
KB of code size. / 0: Disable / 1: Enable
*/
#define JD_FASTDECODE 1
/* Optimization level
/ 0: Basic optimization. Suitable for 8/16-bit MCUs.
/ Workspace of 3100 bytes needed.
/ 1: + 32-bit barrel shifter. Suitable for 32-bit MCUs.
/ Workspace of 3480 bytes needed.
/ 2: + Table conversion for huffman decoding (wants 6 << HUFF_BIT bytes of
RAM). / Workspace of 9644 bytes needed.
*/
// Do not change this, it is the minimum size in bytes of the workspace needed
// by the decoder
#if JD_FASTDECODE == 0
#define TJPGD_WORKSPACE_SIZE 3100
#elif JD_FASTDECODE == 1
#define TJPGD_WORKSPACE_SIZE 3500
#elif JD_FASTDECODE == 2
#define TJPGD_WORKSPACE_SIZE (3500 + 6144)
#endif

View file

@ -0,0 +1,46 @@
This directory is intended for project specific (private) libraries.
PlatformIO will compile them to static libraries and link into executable file.
The source code of each library should be placed in a an own separate directory
("lib/your_library_name/[here are source files]").
For example, see a structure of the following two libraries `Foo` and `Bar`:
|--lib
| |
| |--Bar
| | |--docs
| | |--examples
| | |--src
| | |- Bar.c
| | |- Bar.h
| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html
| |
| |--Foo
| | |- Foo.c
| | |- Foo.h
| |
| |- README --> THIS FILE
|
|- platformio.ini
|--src
|- main.c
and a contents of `src/main.c`:
```
#include <Foo.h>
#include <Bar.h>
int main (void)
{
...
}
```
PlatformIO Library Dependency Finder will find automatically dependent
libraries scanning project source files.
More information about PlatformIO Library Dependency Finder
- https://docs.platformio.org/page/librarymanager/ldf.html

View file

@ -0,0 +1,5 @@
# Name, Type, SubType, Offset, Size, Flags
nvs, data, nvs, 0x9000, 0x5000,
otadata, data, ota, 0xe000, 0x2000,
app0, app, ota_0, 0x10000, 0x3d0000,
fr, data, , 0x3e0000, 0x20000,
1 # Name Type SubType Offset Size Flags
2 nvs data nvs 0x9000 0x5000
3 otadata data ota 0xe000 0x2000
4 app0 app ota_0 0x10000 0x3d0000
5 fr data 0x3e0000 0x20000

View file

@ -0,0 +1,31 @@
; PlatformIO Project Configuration File for MEMENTO/PyCamera
;
; Build options: build flags, source filter
; Upload options: custom upload port, speed and extra flags
; Library options: dependencies, extra library storages
; Advanced options: extra scripting
;
; Please visit documentation for the other options and examples
; https://docs.platformio.org/page/projectconf.html
[env:adafruit_camera_esp32s3]
platform = espressif32 @ ^6.5.0
board = adafruit_camera_esp32s3
framework = arduino
upload_port = /dev/cu.usbmodem13301
monitor_port = /dev/cu.usbmodem13301
monitor_speed = 115200
board_upload.before_reset = default_reset
build_flags = -DBOARD_HAS_PSRAM -mfix-esp32-psram-cache-issue -DARDUINO_LOOP_STACK_SIZE=8092
board_build.partitions = partitions.csv
lib_deps = adafruit/Adafruit AW9523
adafruit/Adafruit NeoPixel
Wire
SPI
adafruit/Adafruit BusIO
adafruit/Adafruit GFX Library
adafruit/Adafruit ST7735 and ST7789 Library
adafruit/SdFat - Adafruit Fork
adafruit/Adafruit GFX Library
https://github.com/adafruit/Adafruit-ST7735-Library
https://github.com/adafruit/Adafruit_NeoPixel.git

View file

@ -0,0 +1,376 @@
// SPDX-FileCopyrightText: 2018 me-no-dev for Espressif Systems
//
// SPDX-License-Identifier: LGPL 2.1
//
// Modified by Brent Rubell for Adafruit Industries
#include "TJpg_Decoder.h"
#include "esp_camera.h"
#include "face_recognition_112_v1_s8.hpp"
#include "face_recognition_tool.hpp"
#include "fb_gfx.h"
#include "human_face_detect_mnp01.hpp"
#include "human_face_detect_msr01.hpp"
#include "ra_filter.h"
#include <Adafruit_GFX.h>
#include <Adafruit_NeoPixel.h>
#include <Adafruit_ST7789.h>
#include <SPI.h>
#include <WiFi.h>
#include <Wire.h>
#include <vector>
// The number of faces to save
// NOTE - these faces are saved to the ESP32's flash memory and survive between
// reboots
#define FACE_ID_SAVE_NUMBER 4
// Threshold (0.0 - 1.0) to determine whether the face detected is a positive
// match NOTE - This value is adjustable, you may "tune" it for either a more
// confident match
#define FR_CONFIDENCE_THRESHOLD 0.7
// True if you want to save faces to flash memory and load them on boot, False
// otherwise
#define SAVE_FACES_TO_FLASH false
// NeoPixel ring used to indicate face recognition status
#define PIXELS_PIN A1
#define NUMPIXELS 12
// NeoPixel brightness, from 0 to 225 (0% to 100%)
#define PIXEL_BRIGHTNESS 25
Adafruit_NeoPixel pixels(NUMPIXELS, PIXELS_PIN, NEO_GRB + NEO_KHZ800);
Adafruit_ST7789 tft =
Adafruit_ST7789(TFT_CS, TFT_DC, TFT_RESET); ///< TFT display
/**************************************************************************/
/**
* @brief Framebuffer class for PyCamera.
*
* @details This class extends GFXcanvas16 to provide a framebuffer for the
* PyCamera.
*/
/**************************************************************************/
class PyCameraFB : public GFXcanvas16 {
public:
/**************************************************************************/
/**
* @brief Construct a new PyCameraFB object.
*
* @param w Width of the framebuffer.
* @param h Height of the framebuffer.
*/
/**************************************************************************/
PyCameraFB(uint16_t w, uint16_t h) : GFXcanvas16(w, h) {
free(buffer);
buffer = NULL;
};
/**************************************************************************/
/**
* @brief Set the framebuffer.
*
* @param fb Pointer to the framebuffer data.
*/
/**************************************************************************/
void setFB(uint16_t *fb) { buffer = fb; }
};
/**** FR and FD ****/
// pointer to the camera's framebuffer
camera_fb_t *fb = NULL;
// pointer to the TFT's framebuffer
PyCameraFB *pyCameraFb = NULL;
// Recognizer model
// S8 model - faster but less accurate
FaceRecognition112V1S8 recognizer;
// Use two-stage fd and weights
HumanFaceDetectMSR01 s1(0.1F, 0.5F, 10, 0.2F);
HumanFaceDetectMNP01 s2(0.5F, 0.3F, 5);
static int8_t is_enrolling = 0; // 0: not enrolling, 1: enrolling
/*
* @brief Draws face boxes and landmarks on the framebuffer, modified to work
* with ST7789 TFT display.
*
* @param fb Pointer to the framebuffer data.
* @param results Pointer to the list of detected faces.
* @param face_id The ID of the detected face.
*/
static void draw_face_boxes(fb_data_t *fb,
std::list<dl::detect::result_t> *results,
int face_id) {
int x, y, w, h;
uint32_t color = ST77XX_YELLOW;
if (face_id < 0) {
color = ST77XX_RED;
} else if (face_id > 0) {
color = ST77XX_GREEN;
}
if (fb->bytes_per_pixel == 2) {
// color = ((color >> 8) & 0xF800) | ((color >> 3) & 0x07E0) | (color &
// 0x001F);
color = ((color >> 16) & 0x001F) | ((color >> 3) & 0x07E0) |
((color << 8) & 0xF800);
}
int i = 0;
for (std::list<dl::detect::result_t>::iterator prediction = results->begin();
prediction != results->end(); prediction++, i++) {
// create boxes
x = (int)prediction->box[0];
y = (int)prediction->box[1];
w = (int)prediction->box[2] - x + 1;
h = (int)prediction->box[3] - y + 1;
if ((x + w) > fb->width) {
w = fb->width - x;
}
if ((y + h) > fb->height) {
h = fb->height - y;
}
// draw boxes
tft.drawFastHLine(x, y, w, color);
tft.drawFastHLine(x, y + h - 1, w, color);
tft.drawFastVLine(x, y, h, color);
tft.drawFastVLine(x + w - 1, y, h, color);
// draw landmarks (left eye, mouth left, nose, right eye, mouth right)
int x0, y0, j;
for (j = 0; j < 10; j += 2) {
x0 = (int)prediction->keypoint[j];
y0 = (int)prediction->keypoint[j + 1];
tft.fillRect(x0, y0, 3, 3, color);
}
}
}
/**
* @brief Run face recognition on the framebuffer.
*
* @param fb Pointer to the framebuffer data.
* @param results Pointer to the list of detected faces.
* @return int The ID of the recognized face.
*/
static int run_face_recognition(fb_data_t *fb,
std::list<dl::detect::result_t> *results) {
std::vector<int> landmarks = results->front().keypoint;
int id = -1;
(void)id;
Tensor<uint8_t> tensor;
tensor.set_element((uint8_t *)fb->data)
.set_shape({fb->height, fb->width, 3})
.set_auto_free(false);
int enrolled_count = recognizer.get_enrolled_id_num();
if (enrolled_count < FACE_ID_SAVE_NUMBER && is_enrolling) {
int id = recognizer.enroll_id(tensor, landmarks, "", true);
(void)id;
Serial.printf("Enrolled ID: %d", id);
tft.setCursor(0, 230);
tft.setTextColor(ST77XX_CYAN);
tft.print("Enrolled a new face with ID #");
tft.print(id);
is_enrolling = false;
} else if (enrolled_count > FACE_ID_SAVE_NUMBER) {
Serial.println(
"ERROR: Already enrolled the maximum number of faces, can not "
"enroll more!");
}
face_info_t recognize = recognizer.recognize(tensor, landmarks);
if (recognize.id >= 0 && recognize.similarity >= FR_CONFIDENCE_THRESHOLD) {
// Face was recognized, print out to serial and TFT
Serial.printf("Recognized ID: %d", recognize.id);
Serial.printf("with similarity of: %0.2f", recognize.similarity);
tft.setCursor(0, 220);
tft.setTextColor(ST77XX_CYAN);
tft.print("Recognized Face ID #");
tft.print(id);
tft.print("\nSimilarity: ");
tft.print(recognize.similarity);
// Set pixel ring to green to indicate a recognized face
for (int i = 0; i <= NUMPIXELS; i++) {
pixels.setPixelColor(i, pixels.Color(0, 255, 0));
}
pixels.show();
delay(2500);
} else if (recognizer.get_enrolled_id_num() > 0) {
// Face was not recognized but we have faces enrolled
Serial.println("Intruder alert - face not recognized as an enrolled face!");
Serial.printf("This face has a similarity of: %0.2f\n",
recognize.similarity);
// Set pixel ring to green to indicate a recognized face
for (int i = 0; i <= NUMPIXELS; i++) {
pixels.setPixelColor(i, pixels.Color(255, 0, 0));
}
pixels.show();
delay(1000);
} else {
// Face was not recognized and we have nothing enrolled
Serial.println("Face not recognized, but nothing enrolled!");
}
return recognize.id;
}
/**
* @brief Initialize the Adafruit MEMENTO's TFT display
*
* @return True if TFT display initialized successfully, False otherwise.
*/
bool initDisplay() {
pinMode(45, OUTPUT);
digitalWrite(45, LOW);
tft.init(240, 240); // Initialize ST7789 screen
tft.setRotation(1);
tft.fillScreen(ST77XX_GREEN);
digitalWrite(45, HIGH);
return true;
}
bool initCamera() {
Wire.begin(34, 33);
pinMode(SHUTTER_BUTTON, INPUT_PULLUP);
camera_config_t config;
config.ledc_channel = LEDC_CHANNEL_0;
config.ledc_timer = LEDC_TIMER_0;
config.pin_d0 = Y2_GPIO_NUM;
config.pin_d1 = Y3_GPIO_NUM;
config.pin_d2 = Y4_GPIO_NUM;
config.pin_d3 = Y5_GPIO_NUM;
config.pin_d4 = Y6_GPIO_NUM;
config.pin_d5 = Y7_GPIO_NUM;
config.pin_d6 = Y8_GPIO_NUM;
config.pin_d7 = Y9_GPIO_NUM;
config.pin_xclk = XCLK_GPIO_NUM;
config.pin_pclk = PCLK_GPIO_NUM;
config.pin_vsync = VSYNC_GPIO_NUM;
config.pin_href = HREF_GPIO_NUM;
config.pin_sccb_sda = -1;
config.pin_sccb_scl = -1;
// use the built in I2C port
// config.sccb_i2c_port = 0; // use the 'first' i2c port
config.pin_pwdn = 21;
config.pin_reset = 47;
config.xclk_freq_hz = 20000000;
config.grab_mode = CAMERA_GRAB_WHEN_EMPTY;
config.fb_location = CAMERA_FB_IN_PSRAM;
config.frame_size = FRAMESIZE_240X240;
config.pixel_format = PIXFORMAT_RGB565;
config.fb_count = 2;
// Initialize the camera
esp_err_t err = esp_camera_init(&config);
if (err != ESP_OK) {
Serial.printf("ERROR: Camera init failed with code 0x%x", err);
return false;
}
// Configure the camera's sensor
sensor_t *s = esp_camera_sensor_get();
s->set_vflip(s, 1);
s->set_hmirror(s, 0);
return true;
}
void setup() {
Serial.begin(115200);
Serial.println();
if (!initCamera()) {
Serial.println("Camera init failed!");
}
if (!initDisplay()) {
Serial.println("Display init failed!");
}
// Initialize the TFT's framebuffer
pyCameraFb = new PyCameraFB(240, 240);
// Initialize NeoPixel ring
pixels.begin();
pixels.clear();
pixels.show();
pixels.setBrightness(PIXEL_BRIGHTNESS);
// Initialize face recognition filter and partition
ra_filter_init(&ra_filter, 20);
recognizer.set_partition(ESP_PARTITION_TYPE_DATA, ESP_PARTITION_SUBTYPE_ANY,
"fr");
#ifdef SAVE_FACES_TO_FLASH
// Optionally load face ids from flash partition
recognizer.set_ids_from_flash();
#endif
}
void loop() {
// If the shutter button is pressed, enroll a new face
if (digitalRead(SHUTTER_BUTTON) == LOW) {
is_enrolling = true;
// Signal to the user on the TFT and serial that we're enrolling a face
Serial.println("Enrolling face..");
tft.setCursor(0, 230);
tft.setTextColor(ST77XX_CYAN);
tft.print("Enrolling Face...");
// Make pixel ring light up bright white to better capture facial features
for (int i = 0; i <= NUMPIXELS; i++) {
pixels.setPixelColor(i, pixels.Color(255, 255, 255));
}
pixels.show();
}
// capture from the camera into the frame buffer
Serial.printf("Capturing frame...\n");
fb = esp_camera_fb_get();
if (!fb) {
Serial.printf("ERROR: Camera capture failed\n");
} else {
Serial.printf("Frame capture successful!\n");
// Face detection
std::list<dl::detect::result_t> &candidates =
s1.infer((uint16_t *)fb->buf, {(int)fb->height, (int)fb->width, 3});
std::list<dl::detect::result_t> &results = s2.infer(
(uint16_t *)fb->buf, {(int)fb->height, (int)fb->width, 3}, candidates);
if (results.size() > 0) {
Serial.println("Detected face!");
int face_id = 0;
fb_data_t rfb;
rfb.width = fb->width;
rfb.height = fb->height;
rfb.data = fb->buf;
rfb.bytes_per_pixel = 2;
rfb.format = FB_RGB565;
// Face recognition is SLOW! So, only attempt it if we are enrolling a
// new face, or have previously enrolled a face
if (recognizer.get_enrolled_id_num() > 0 || is_enrolling) {
face_id = run_face_recognition(&rfb, &results);
} else {
face_id = 0;
tft.setCursor(0, 230);
tft.setTextColor(ST77XX_GREEN);
tft.print("DETECTED FACE!");
}
// Draw face detection boxes and landmarks on the framebuffer
draw_face_boxes(&rfb, &results, face_id);
// Turn off pixel ring after we've detected a face
pixels.clear();
pixels.show();
}
}
// Blit framebuffer to TFT
uint8_t temp;
for (uint32_t i = 0; i < fb->len; i += 2) {
temp = fb->buf[i + 0];
fb->buf[i + 0] = fb->buf[i + 1];
fb->buf[i + 1] = temp;
}
pyCameraFb->setFB((uint16_t *)fb->buf);
tft.drawRGBBitmap(0, 0, (uint16_t *)pyCameraFb->getBuffer(), 240, 240);
// Release the framebuffer
esp_camera_fb_return(fb);
}

View file

@ -0,0 +1,38 @@
// RA Filtering
typedef struct {
size_t size; // number of values used for filtering
size_t index; // current value index
size_t count; // value count
int sum;
int *values; // array to be filled with values
} ra_filter_t;
static ra_filter_t ra_filter;
static ra_filter_t *ra_filter_init(ra_filter_t *filter, size_t sample_size) {
memset(filter, 0, sizeof(ra_filter_t));
filter->values = (int *)malloc(sample_size * sizeof(int));
if (!filter->values) {
return NULL;
}
memset(filter->values, 0, sample_size * sizeof(int));
filter->size = sample_size;
return filter;
}
static int ra_filter_run(ra_filter_t *filter, int value) {
if (!filter->values) {
return value;
}
filter->sum -= filter->values[filter->index];
filter->values[filter->index] = value;
filter->sum += filter->values[filter->index];
filter->index++;
filter->index = filter->index % filter->size;
if (filter->count < filter->size) {
filter->count++;
}
return filter->sum / filter->count;
}

View file

@ -0,0 +1,11 @@
This directory is intended for PlatformIO Test Runner and project tests.
Unit Testing is a software testing method by which individual units of
source code, sets of one or more MCU program modules together with associated
control data, usage procedures, and operating procedures, are tested to
determine whether they are fit for use. Unit testing finds problems early
in the development cycle.
More information about PlatformIO Unit Testing:
- https://docs.platformio.org/en/latest/advanced/unit-testing/index.html