init
This commit is contained in:
18
.vscode/c_cpp_properties.json
vendored
Normal file
18
.vscode/c_cpp_properties.json
vendored
Normal file
@@ -0,0 +1,18 @@
|
||||
{
|
||||
"configurations": [
|
||||
{
|
||||
"name": "windows-gcc-x86",
|
||||
"includePath": [
|
||||
"${workspaceFolder}/**"
|
||||
],
|
||||
"compilerPath": "C:/MinGW/bin/gcc.exe",
|
||||
"cStandard": "${default}",
|
||||
"cppStandard": "${default}",
|
||||
"intelliSenseMode": "windows-gcc-x86",
|
||||
"compilerArgs": [
|
||||
""
|
||||
]
|
||||
}
|
||||
],
|
||||
"version": 4
|
||||
}
|
24
.vscode/launch.json
vendored
Normal file
24
.vscode/launch.json
vendored
Normal file
@@ -0,0 +1,24 @@
|
||||
{
|
||||
"version": "0.2.0",
|
||||
"configurations": [
|
||||
{
|
||||
"name": "C/C++ Runner: Debug Session",
|
||||
"type": "cppdbg",
|
||||
"request": "launch",
|
||||
"args": [],
|
||||
"stopAtEntry": false,
|
||||
"externalConsole": true,
|
||||
"cwd": "d:/Users/micha/Desktop/Projects/CanSat/Programming/lepton_2",
|
||||
"program": "d:/Users/micha/Desktop/Projects/CanSat/Programming/lepton_2/build/Debug/outDebug",
|
||||
"MIMode": "gdb",
|
||||
"miDebuggerPath": "gdb",
|
||||
"setupCommands": [
|
||||
{
|
||||
"description": "Enable pretty-printing for gdb",
|
||||
"text": "-enable-pretty-printing",
|
||||
"ignoreFailures": true
|
||||
}
|
||||
]
|
||||
}
|
||||
]
|
||||
}
|
59
.vscode/settings.json
vendored
Normal file
59
.vscode/settings.json
vendored
Normal file
@@ -0,0 +1,59 @@
|
||||
{
|
||||
"C_Cpp_Runner.cCompilerPath": "gcc",
|
||||
"C_Cpp_Runner.cppCompilerPath": "g++",
|
||||
"C_Cpp_Runner.debuggerPath": "gdb",
|
||||
"C_Cpp_Runner.cStandard": "",
|
||||
"C_Cpp_Runner.cppStandard": "",
|
||||
"C_Cpp_Runner.msvcBatchPath": "",
|
||||
"C_Cpp_Runner.useMsvc": false,
|
||||
"C_Cpp_Runner.warnings": [
|
||||
"-Wall",
|
||||
"-Wextra",
|
||||
"-Wpedantic",
|
||||
"-Wshadow",
|
||||
"-Wformat=2",
|
||||
"-Wcast-align",
|
||||
"-Wconversion",
|
||||
"-Wsign-conversion",
|
||||
"-Wnull-dereference"
|
||||
],
|
||||
"C_Cpp_Runner.msvcWarnings": [
|
||||
"/W4",
|
||||
"/permissive-",
|
||||
"/w14242",
|
||||
"/w14287",
|
||||
"/w14296",
|
||||
"/w14311",
|
||||
"/w14826",
|
||||
"/w44062",
|
||||
"/w44242",
|
||||
"/w14905",
|
||||
"/w14906",
|
||||
"/w14263",
|
||||
"/w44265",
|
||||
"/w14928"
|
||||
],
|
||||
"C_Cpp_Runner.enableWarnings": true,
|
||||
"C_Cpp_Runner.warningsAsError": false,
|
||||
"C_Cpp_Runner.compilerArgs": [],
|
||||
"C_Cpp_Runner.linkerArgs": [],
|
||||
"C_Cpp_Runner.includePaths": [],
|
||||
"C_Cpp_Runner.includeSearch": [
|
||||
"*",
|
||||
"**/*"
|
||||
],
|
||||
"C_Cpp_Runner.excludeSearch": [
|
||||
"**/build",
|
||||
"**/build/**",
|
||||
"**/.*",
|
||||
"**/.*/**",
|
||||
"**/.vscode",
|
||||
"**/.vscode/**"
|
||||
],
|
||||
"C_Cpp_Runner.useAddressSanitizer": false,
|
||||
"C_Cpp_Runner.useUndefinedSanitizer": false,
|
||||
"C_Cpp_Runner.useLeakSanitizer": false,
|
||||
"C_Cpp_Runner.showCompilationTime": false,
|
||||
"C_Cpp_Runner.useLinkTimeOptimization": false,
|
||||
"C_Cpp_Runner.msvcSecureNoWarnings": false
|
||||
}
|
182
lepton_img2serial.ino
Normal file
182
lepton_img2serial.ino
Normal file
@@ -0,0 +1,182 @@
|
||||
#include <stdbool.h>
|
||||
#include "esp_system.h"
|
||||
|
||||
#include "src/lipton/cci.h"
|
||||
#include "src/lipton/vospi.h"
|
||||
#include "src/lipton/lepton_system.h"
|
||||
#include "src/lipton/lepton_utilities.h"
|
||||
|
||||
|
||||
#include "mbedtls/base64.h"
|
||||
|
||||
|
||||
//
|
||||
// LEP Task constants
|
||||
//
|
||||
|
||||
// Number of consecutive VoSPI resynchronization attempts before attempting to reset
|
||||
#define LEP_SYNC_FAIL_FAULT_LIMIT 10
|
||||
|
||||
// Reset fail delay before attempting a re-init (seconds)
|
||||
#define LEP_RESET_FAIL_RETRY_SECS 5
|
||||
|
||||
|
||||
//
|
||||
// picture functions
|
||||
//
|
||||
char* base64_encode_lep_image(uint16_t* lep_bufferP, size_t* base64_length) {
|
||||
size_t base64_obj_len = 0;
|
||||
char* base64_lep_data = NULL;
|
||||
|
||||
// Get the necessary length for base64 encoding
|
||||
mbedtls_base64_encode(NULL, 0, &base64_obj_len, (const unsigned char*)lep_bufferP, LEP_NUM_PIXELS * 2);
|
||||
|
||||
// Allocate memory for the base64 encoded data
|
||||
base64_lep_data = (char*)malloc(base64_obj_len);
|
||||
if (base64_lep_data == NULL) {
|
||||
return NULL; // Memory allocation failed
|
||||
}
|
||||
|
||||
// Base64 encode the camera data
|
||||
if (mbedtls_base64_encode((unsigned char*)base64_lep_data, base64_obj_len, &base64_obj_len, (const unsigned char*)lep_bufferP, LEP_NUM_PIXELS * 2) != 0) {
|
||||
free(base64_lep_data);
|
||||
return NULL; // Encoding failed
|
||||
}
|
||||
|
||||
*base64_length = base64_obj_len;
|
||||
|
||||
return base64_lep_data;
|
||||
}
|
||||
|
||||
void pic_to_uart(uint16_t* pic_buf) {
|
||||
size_t base64_length = 0;
|
||||
char* base64_encoded_data = base64_encode_lep_image(pic_buf, &base64_length);
|
||||
|
||||
if (base64_encoded_data != NULL) {
|
||||
// Output the base64 encoded string and its length
|
||||
printf("data:base64,%s\n", base64_encoded_data);
|
||||
|
||||
// Remember to free the allocated memory
|
||||
free(base64_encoded_data);
|
||||
}
|
||||
}
|
||||
|
||||
//
|
||||
// Code start
|
||||
//
|
||||
int vsync_count = 0;
|
||||
int sync_fail_count = 0;
|
||||
int reset_fail_count = 0;
|
||||
int64_t vsyncDetectedUsec;
|
||||
|
||||
void setup() {
|
||||
printf("[MAIN] Start task\n");
|
||||
|
||||
LEP_CONFIG = {
|
||||
.agc_set_enabled = false,
|
||||
.emissivity = 100,
|
||||
.gain_mode = LEP_GAIN_AUTO
|
||||
};
|
||||
|
||||
// initialize spi, i2c and gpio for lepton
|
||||
if (!lepton_io_init()) {
|
||||
printf("[MAIN] Error: I/O init failed");
|
||||
while(1) {delay(100);}
|
||||
}
|
||||
|
||||
// allocate lepton buffers
|
||||
if (!lepton_buffer_init()) {
|
||||
printf("[MAIN] Error: Memory init failed");
|
||||
while(1) {delay(100);}
|
||||
}
|
||||
|
||||
// wait for lepton to initialize
|
||||
delay(1000);
|
||||
|
||||
// Attempt to initialize the VoSPI interface
|
||||
if (vospi_init() != ESP_OK) {
|
||||
printf("[MAIN] Error: Lepton VoSPI initialization failed\n");
|
||||
while(1) {delay(100);}
|
||||
}
|
||||
|
||||
// initialize lepton
|
||||
if (!lepton_init()) {
|
||||
printf("[MAIN] Error: Lepton CCI initialization failed\n");
|
||||
while(1) {delay(100);}
|
||||
}
|
||||
|
||||
// disable data from lepton
|
||||
digitalWrite(LEP_CSN_PIN, 1);
|
||||
}
|
||||
|
||||
uint16_t* take_picture() {
|
||||
digitalWrite(LEP_CSN_PIN, 0);
|
||||
delay(10);
|
||||
|
||||
while (1) {
|
||||
// Spin waiting for vsync to be asserted
|
||||
int t = 0;
|
||||
while (digitalRead(LEP_VSYNC_PIN) == 0 && t++ < 500) {}
|
||||
|
||||
vsyncDetectedUsec = esp_timer_get_time();
|
||||
|
||||
// Attempt to process a segment
|
||||
if (t >= 500 || vospi_transfer_segment(vsyncDetectedUsec)) {
|
||||
// Got image
|
||||
vsync_count = 0;
|
||||
|
||||
// Copy the frame to the current half of the shared buffer and let rsp_task know
|
||||
vospi_get_frame(&rsp_lep_buffer);
|
||||
|
||||
// Hold fault counters reset while operating
|
||||
sync_fail_count = 0;
|
||||
|
||||
// disable lepton again
|
||||
digitalWrite(LEP_CSN_PIN, 1);
|
||||
return rsp_lep_buffer.lep_bufferP;
|
||||
} else {
|
||||
if (++vsync_count >= 36) {
|
||||
vsync_count = 0;
|
||||
printf("[MAIN] Could not get lepton image\n");
|
||||
|
||||
delay(185);
|
||||
|
||||
if (sync_fail_count++ == LEP_SYNC_FAIL_FAULT_LIMIT) {
|
||||
return nullptr;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
int lepton_restart() {
|
||||
while (1) {
|
||||
delay(LEP_RESET_FAIL_RETRY_SECS*1000);
|
||||
|
||||
// Assert hardware reset
|
||||
digitalWrite(LEP_RESET_PIN, LEP_RESET_ON);
|
||||
delay(10);
|
||||
digitalWrite(LEP_RESET_PIN, LEP_RESET_OFF);
|
||||
|
||||
|
||||
// Delay for Lepton internal initialization (max 950 mSec)
|
||||
delay(1000);
|
||||
|
||||
// if successfully initialized, break out
|
||||
if (lepton_init())
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void loop() {
|
||||
delay(5000);
|
||||
|
||||
uint16_t* picture = take_picture();
|
||||
if (picture) {
|
||||
pic_to_uart(picture);
|
||||
} else {
|
||||
lepton_restart();
|
||||
}
|
||||
}
|
794
src/lipton/cci.cpp
Normal file
794
src/lipton/cci.cpp
Normal file
@@ -0,0 +1,794 @@
|
||||
/*
|
||||
* Lepton CCI Module
|
||||
*
|
||||
* Contains the functions to configure the Lepton via I2C.
|
||||
*
|
||||
* Copyright 2020-2022 Dan Julio
|
||||
*
|
||||
* This file is part of tCam.
|
||||
*
|
||||
* tCam is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* tCam is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with tCam. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#include "cci.h"
|
||||
#include "i2c.h"
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <Arduino.h>
|
||||
|
||||
#define CCI_MAX_WAIT_TICKS 5000
|
||||
|
||||
//
|
||||
// CCI Variables
|
||||
//
|
||||
static bool cci_last_status_error;
|
||||
static uint16_t cci_last_status;
|
||||
|
||||
// Statically allocated burst read/write I2C buffer sized for up to 512 16-bit words
|
||||
// plus register starting address
|
||||
static uint8_t burst_buf[1026];
|
||||
|
||||
|
||||
|
||||
//
|
||||
// Forward declarations for primitive access methods
|
||||
//
|
||||
static int cci_write_register(uint16_t reg, uint16_t value);
|
||||
static int cci_write_burst(uint16_t start, uint16_t word_len, uint16_t* buf);
|
||||
static uint16_t cci_read_register(uint16_t reg);
|
||||
static int cci_read_burst(uint16_t start, uint16_t word_len, uint16_t* buf);
|
||||
static uint32_t cci_wait_busy_clear();
|
||||
static void cci_wait_busy_clear_check(char* cmd);
|
||||
|
||||
|
||||
|
||||
//
|
||||
// CCI API
|
||||
//
|
||||
|
||||
|
||||
/**
|
||||
* Write 0 (equivalent to run_cmd) to 512 16-bit words to the lepton and issue
|
||||
* the specified command. Lengths > 16 words are written to the BLOCK data buffer.
|
||||
*/
|
||||
void cci_set_reg(uint16_t cmd, int len, uint16_t* buf)
|
||||
{
|
||||
char cmd_buf[11]; // sized for 'cmd 0xNNNN<NULL>'
|
||||
int ret = 1;
|
||||
|
||||
cci_last_status_error = false;
|
||||
|
||||
cci_wait_busy_clear();
|
||||
|
||||
if ((len > 0) && (len <= 16)) {
|
||||
ret = cci_write_burst(CCI_REG_DATA_0, len, buf);
|
||||
} else if ((len > 16) && (len <= 512)) {
|
||||
ret = cci_write_burst(CCI_BLOCK_BUF_0, len, buf);
|
||||
} else if (len > 512) {
|
||||
ret = 0;
|
||||
}
|
||||
|
||||
if (ret == 1) {
|
||||
if (len > 0) {
|
||||
sprintf(cmd_buf, "CMD 0x%4x\n", cmd);
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, len);
|
||||
} else {
|
||||
sprintf(cmd_buf, "RUN 0x%4x\n", cmd);
|
||||
}
|
||||
|
||||
cci_write_register(CCI_REG_COMMAND, cmd);
|
||||
cci_wait_busy_clear_check(cmd_buf);
|
||||
} else {
|
||||
cci_last_status = 0;
|
||||
cci_last_status_error = true;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Read up to 512 16-bit words form the lepton with the specified command. Lengths > 16
|
||||
* words are read from the BLOCK data buffer.
|
||||
*/
|
||||
void cci_get_reg(uint16_t cmd, int len, uint16_t* buf)
|
||||
{
|
||||
char cmd_buf[11]; // sized for 'cmd 0xNNNN<NULL>'
|
||||
|
||||
sprintf(cmd_buf, "CMD 0x%4x", cmd);
|
||||
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, len);
|
||||
cci_write_register(CCI_REG_COMMAND, cmd);
|
||||
cci_wait_busy_clear_check(cmd_buf);
|
||||
if ((len > 0) && (len <= 16)) {
|
||||
(void) cci_read_burst(CCI_REG_DATA_0, len, buf);
|
||||
} else if ((len > 16) && (len <= 512)) {
|
||||
(void) cci_read_burst(CCI_BLOCK_BUF_0, len, buf);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Return true if previous command succeeded as detected by cci_wait_busy_clear_check
|
||||
*/
|
||||
bool cci_command_success(uint16_t* status)
|
||||
{
|
||||
*status = cci_last_status;
|
||||
return !cci_last_status_error;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Ping the camera.
|
||||
* Returns 0 for a successful ping
|
||||
* Returns the absolute (postive) 8-bit non-zero LEP_RESULT for a failure
|
||||
* Returns 0x100 (256) for a communications failure
|
||||
*/
|
||||
uint32_t cci_run_ping()
|
||||
{
|
||||
uint32_t res;
|
||||
uint8_t lep_res;
|
||||
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_SYS_RUN_PING);
|
||||
res = cci_wait_busy_clear();
|
||||
|
||||
lep_res = (res & 0x000FF00) >> 8; // 8-bit Response Error Code: 0=LEP_OK
|
||||
if (res == 0x00010000) {
|
||||
return 0x100;
|
||||
} else if (lep_res == 0x00) {
|
||||
return 0;
|
||||
} else {
|
||||
// Convert negative Lepton Response Error Code to a positive number to return
|
||||
lep_res = ~lep_res + 1;
|
||||
return lep_res;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Request that a flat field correction occur immediately.
|
||||
*/
|
||||
void cci_run_ffc()
|
||||
{
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_SYS_RUN_FFC);
|
||||
cci_wait_busy_clear_check("CCI_CMD_SYS_RUN_FFC");
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Get the system uptime.
|
||||
*/
|
||||
uint32_t cci_get_uptime()
|
||||
{
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_SYS_GET_UPTIME);
|
||||
cci_wait_busy_clear_check("CCI_CMD_SYS_GET_UPTIME");
|
||||
|
||||
uint16_t ls_word = cci_read_register(CCI_REG_DATA_0);
|
||||
uint16_t ms_word = cci_read_register(CCI_REG_DATA_1);
|
||||
return ms_word << 16 | ls_word;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Get the AUX (case) temperature in Kelvin x 100 (16-bit result).
|
||||
*/
|
||||
uint32_t cci_get_aux_temp()
|
||||
{
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_SYS_GET_AUX_TEMP);
|
||||
cci_wait_busy_clear_check("CCI_CMD_SYS_GET_AUX_TEMP");
|
||||
|
||||
uint16_t ls_word = cci_read_register(CCI_REG_DATA_0);
|
||||
uint16_t ms_word = cci_read_register(CCI_REG_DATA_1);
|
||||
return ms_word << 16 | ls_word;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Get the FPA (sensor) temperature in Kelvin x 100 (16-bit result).
|
||||
*/
|
||||
uint32_t cci_get_fpa_temp()
|
||||
{
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_SYS_GET_FPA_TEMP);
|
||||
cci_wait_busy_clear_check("CCI_CMD_SYS_GET_FPA_TEMP");
|
||||
|
||||
uint16_t ls_word = cci_read_register(CCI_REG_DATA_0);
|
||||
uint16_t ms_word = cci_read_register(CCI_REG_DATA_1);
|
||||
return ms_word << 16 | ls_word;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Change the telemetry enable state.
|
||||
*/
|
||||
void cci_set_telemetry_enable_state(cci_telemetry_enable_state_t state)
|
||||
{
|
||||
uint32_t value = state;
|
||||
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_0, value & 0xffff);
|
||||
cci_write_register(CCI_REG_DATA_1, value >> 16 & 0xffff);
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_SYS_SET_TELEMETRY_ENABLE_STATE);
|
||||
cci_wait_busy_clear_check("CCI_CMD_SYS_SET_TELEMETRY_ENABLE_STATE");
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Get the telemetry enable state.
|
||||
*/
|
||||
uint32_t cci_get_telemetry_enable_state()
|
||||
{
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_SYS_GET_TELEMETRY_ENABLE_STATE);
|
||||
cci_wait_busy_clear_check("CCI_CMD_SYS_GET_TELEMETRY_ENABLE_STATE");
|
||||
|
||||
uint16_t ls_word = cci_read_register(CCI_REG_DATA_0);
|
||||
uint16_t ms_word = cci_read_register(CCI_REG_DATA_1);
|
||||
return ms_word << 16 | ls_word;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Change the telemetry location.
|
||||
*/
|
||||
void cci_set_telemetry_location(cci_telemetry_location_t location)
|
||||
{
|
||||
uint32_t value = location;
|
||||
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_0, value & 0xffff);
|
||||
cci_write_register(CCI_REG_DATA_1, value >> 16 & 0xffff);
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_SYS_SET_TELEMETRY_LOCATION);
|
||||
cci_wait_busy_clear_check("CCI_CMD_SYS_SET_TELEMETRY_LOCATION");
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Get the telemetry location.
|
||||
*/
|
||||
uint32_t cci_get_telemetry_location()
|
||||
{
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_SYS_GET_TELEMETRY_LOCATION);
|
||||
cci_wait_busy_clear_check("CCI_CMD_SYS_GET_TELEMETRY_LOCATION");
|
||||
|
||||
uint16_t ls_word = cci_read_register(CCI_REG_DATA_0);
|
||||
uint16_t ms_word = cci_read_register(CCI_REG_DATA_1);
|
||||
return ms_word << 16 | ls_word;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Get the Gain Mode
|
||||
*/
|
||||
void cci_set_gain_mode(cc_gain_mode_t mode)
|
||||
{
|
||||
uint32_t value = mode;
|
||||
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_0, value & 0xffff);
|
||||
cci_write_register(CCI_REG_DATA_1, value >> 16 & 0xffff);
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_SYS_SET_GAIN_MODE);
|
||||
cci_wait_busy_clear_check("CCI_CMD_SYS_SET_GAIN_MODE");
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Set the gain mode
|
||||
*/
|
||||
uint32_t cci_get_gain_mode()
|
||||
{
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_SYS_GET_GAIN_MODE);
|
||||
cci_wait_busy_clear_check("CCI_CMD_SYS_GET_GAIN_MODE");
|
||||
|
||||
uint16_t ls_word = cci_read_register(CCI_REG_DATA_0);
|
||||
uint16_t ms_word = cci_read_register(CCI_REG_DATA_1);
|
||||
return ms_word << 16 | ls_word;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Change the radiometry enable state.
|
||||
*/
|
||||
void cci_set_radiometry_enable_state(cci_radiometry_enable_state_t state)
|
||||
{
|
||||
uint32_t value = state;
|
||||
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_0, value & 0xffff);
|
||||
cci_write_register(CCI_REG_DATA_1, value >> 16 & 0xffff);
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_RAD_SET_RADIOMETRY_ENABLE_STATE);
|
||||
cci_wait_busy_clear_check("CCI_CMD_RAD_SET_RADIOMETRY_ENABLE_STATE");
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Get the radiometry enable state.
|
||||
*/
|
||||
uint32_t cci_get_radiometry_enable_state()
|
||||
{
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_RAD_GET_RADIOMETRY_ENABLE_STATE);
|
||||
cci_wait_busy_clear_check("CCI_CMD_RAD_GET_RADIOMETRY_ENABLE_STATE");
|
||||
|
||||
uint16_t ls_word = cci_read_register(CCI_REG_DATA_0);
|
||||
uint16_t ms_word = cci_read_register(CCI_REG_DATA_1);
|
||||
return ms_word << 16 | ls_word;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Set the radiometry flux parameters
|
||||
*/
|
||||
void cci_set_radiometry_flux_linear_params(cci_rad_flux_linear_params_t* params)
|
||||
{
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_0, params->sceneEmissivity);
|
||||
cci_write_register(CCI_REG_DATA_1, params->TBkgK);
|
||||
cci_write_register(CCI_REG_DATA_2, params->tauWindow);
|
||||
cci_write_register(CCI_REG_DATA_3, params->TWindowK);
|
||||
cci_write_register(CCI_REG_DATA_4, params->tauAtm);
|
||||
cci_write_register(CCI_REG_DATA_5, params->TAtmK);
|
||||
cci_write_register(CCI_REG_DATA_6, params->reflWindow);
|
||||
cci_write_register(CCI_REG_DATA_7, params->TReflK);
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 8);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_RAD_SET_RADIOMETRY_FLUX_LINEAR_PARAMS);
|
||||
cci_wait_busy_clear_check("CCI_CMD_RAD_SET_RADIOMETRY_FLUX_LINEAR_PARAMS");
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Get the radiometry flux parameters
|
||||
*/
|
||||
bool cci_get_radiometry_flux_linear_params(cci_rad_flux_linear_params_t* params)
|
||||
{
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 8);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_RAD_GET_RADIOMETRY_FLUX_LINEAR_PARAMS);
|
||||
cci_wait_busy_clear_check("CCI_CMD_RAD_GET_RADIOMETRY_FLUX_LINEAR_PARAMS");
|
||||
params->sceneEmissivity = cci_read_register(CCI_REG_DATA_0);
|
||||
params->TBkgK = cci_read_register(CCI_REG_DATA_1);
|
||||
params->tauWindow = cci_read_register(CCI_REG_DATA_2);
|
||||
params->TWindowK = cci_read_register(CCI_REG_DATA_3);
|
||||
params->tauAtm = cci_read_register(CCI_REG_DATA_4);
|
||||
params->TAtmK = cci_read_register(CCI_REG_DATA_5);
|
||||
params->reflWindow = cci_read_register(CCI_REG_DATA_6);
|
||||
params->TReflK = cci_read_register(CCI_REG_DATA_7);
|
||||
|
||||
return !cci_last_status_error;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Change the radiometry TLinear enable state.
|
||||
*/
|
||||
void cci_set_radiometry_tlinear_enable_state(cci_radiometry_tlinear_enable_state_t state)
|
||||
{
|
||||
uint32_t value = state;
|
||||
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_0, value & 0xffff);
|
||||
cci_write_register(CCI_REG_DATA_1, value >> 16 & 0xffff);
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_RAD_SET_RADIOMETRY_TLINEAR_ENABLE_STATE);
|
||||
cci_wait_busy_clear_check("CCI_CMD_RAD_SET_RADIOMETRY_TLINEAR_ENABLE_STATE");
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Get the radiometry TLinear enable state.
|
||||
*/
|
||||
uint32_t cci_get_radiometry_tlinear_enable_state()
|
||||
{
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_RAD_GET_RADIOMETRY_TLINEAR_ENABLE_STATE);
|
||||
cci_wait_busy_clear_check("CCI_CMD_RAD_GET_RADIOMETRY_TLINEAR_ENABLE_STATE");
|
||||
|
||||
uint16_t ls_word = cci_read_register(CCI_REG_DATA_0);
|
||||
uint16_t ms_word = cci_read_register(CCI_REG_DATA_1);
|
||||
return ms_word << 16 | ls_word;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Set the radiometry TLinear Auto Resolution
|
||||
*/
|
||||
void cci_set_radiometry_tlinear_auto_res(cci_radiometry_tlinear_auto_res_state_t state)
|
||||
{
|
||||
uint32_t value = state;
|
||||
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_0, value & 0xffff);
|
||||
cci_write_register(CCI_REG_DATA_1, value >> 16 & 0xffff);
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_RAD_SET_RADIOMETRY_TLINEAR_AUTO_RES);
|
||||
cci_wait_busy_clear_check("CCI_CMD_RAD_SET_RADIOMETRY_TLINEAR_AUTO_RES");
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Get the radiometry TLinear Auto Resolution
|
||||
*/
|
||||
uint32_t cci_get_radiometry_tlinear_auto_res()
|
||||
{
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_RAD_GET_RADIOMETRY_TLINEAR_AUTO_RES);
|
||||
cci_wait_busy_clear_check("CCI_CMD_RAD_GET_RADIOMETRY_TLINEAR_AUTO_RES");
|
||||
|
||||
uint16_t ls_word = cci_read_register(CCI_REG_DATA_0);
|
||||
uint16_t ms_word = cci_read_register(CCI_REG_DATA_1);
|
||||
return ms_word << 16 | ls_word;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Set the Radiometry Spotmeter Region-of-interest
|
||||
*/
|
||||
void cci_set_radiometry_spotmeter(uint16_t r1, uint16_t c1, uint16_t r2, uint16_t c2)
|
||||
{
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_0, r1);
|
||||
cci_write_register(CCI_REG_DATA_1, c1);
|
||||
cci_write_register(CCI_REG_DATA_2, r2);
|
||||
cci_write_register(CCI_REG_DATA_3, c2);
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 4);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_RAD_SET_RADIOMETRY_SPOT_ROI);
|
||||
cci_wait_busy_clear_check("CCI_CMD_RAD_SET_RADIOMETRY_SPOT_ROI");
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Get the Radiometry Spotmeter Region-of-interest
|
||||
*/
|
||||
bool cci_get_radiometry_spotmeter(uint16_t* r1, uint16_t* c1, uint16_t* r2, uint16_t* c2)
|
||||
{
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 4);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_RAD_GET_RADIOMETRY_SPOT_ROI);
|
||||
cci_wait_busy_clear_check("CCI_CMD_RAD_GET_RADIOMETRY_SPOT_ROI");
|
||||
*r1 = cci_read_register(CCI_REG_DATA_0);
|
||||
*c1 = cci_read_register(CCI_REG_DATA_1);
|
||||
*r2 = cci_read_register(CCI_REG_DATA_2);
|
||||
*c2 = cci_read_register(CCI_REG_DATA_3);
|
||||
|
||||
return !cci_last_status_error;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Get the AGC enable state.
|
||||
*/
|
||||
uint32_t cci_get_agc_enable_state()
|
||||
{
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_AGC_GET_AGC_ENABLE_STATE);
|
||||
cci_wait_busy_clear_check("CCI_CMD_AGC_GET_AGC_ENABLE_STATE");
|
||||
|
||||
uint16_t ls_word = cci_read_register(CCI_REG_DATA_0);
|
||||
uint16_t ms_word = cci_read_register(CCI_REG_DATA_1);
|
||||
return ms_word << 16 | ls_word;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Set the AGC enable state.
|
||||
*/
|
||||
void cci_set_agc_enable_state(cci_agc_enable_state_t state)
|
||||
{
|
||||
uint32_t value = state;
|
||||
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_0, value & 0xffff);
|
||||
cci_write_register(CCI_REG_DATA_1, value >> 16 & 0xffff);
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_AGC_SET_AGC_ENABLE_STATE);
|
||||
cci_wait_busy_clear_check("CCI_CMD_AGC_SET_AGC_ENABLE_STATE");
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Get the AGC calc enable state.
|
||||
*/
|
||||
uint32_t cci_get_agc_calc_enable_state()
|
||||
{
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_AGC_GET_CALC_ENABLE_STATE);
|
||||
cci_wait_busy_clear_check("CCI_CMD_AGC_GET_CALC_ENABLE_STATE");
|
||||
|
||||
uint16_t ls_word = cci_read_register(CCI_REG_DATA_0);
|
||||
uint16_t ms_word = cci_read_register(CCI_REG_DATA_1);
|
||||
return ms_word << 16 | ls_word;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Set the AGC calc enable state.
|
||||
*/
|
||||
void cci_set_agc_calc_enable_state(cci_agc_enable_state_t state)
|
||||
{
|
||||
uint32_t value = state;
|
||||
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_0, value & 0xffff);
|
||||
cci_write_register(CCI_REG_DATA_1, value >> 16 & 0xffff);
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_AGC_SET_CALC_ENABLE_STATE);
|
||||
cci_wait_busy_clear_check("CCI_CMD_AGC_SET_CALC_ENABLE_STATE");
|
||||
}
|
||||
|
||||
/**
|
||||
* Run the Reboot command
|
||||
*/
|
||||
void cc_run_oem_reboot()
|
||||
{
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_OEM_RUN_REBOOT);
|
||||
// Sleep to allow camera to reboot and run FFC
|
||||
delay(6000);
|
||||
cci_wait_busy_clear_check("CCI_CMD_OEM_RUN_REBOOT");
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Get the GPIO mode.
|
||||
*/
|
||||
uint32_t cci_get_gpio_mode()
|
||||
{
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_OEM_GET_GPIO_MODE);
|
||||
cci_wait_busy_clear_check("CCI_CMD_OEM_GET_GPIO_MODE");
|
||||
|
||||
uint16_t ls_word = cci_read_register(CCI_REG_DATA_0);
|
||||
uint16_t ms_word = cci_read_register(CCI_REG_DATA_1);
|
||||
return ms_word << 16 | ls_word;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Set the GPIO mode.
|
||||
*/
|
||||
void cci_set_gpio_mode(cci_gpio_mode_t mode)
|
||||
{
|
||||
uint32_t value = mode;
|
||||
|
||||
cci_wait_busy_clear();
|
||||
cci_write_register(CCI_REG_DATA_0, value & 0xffff);
|
||||
cci_write_register(CCI_REG_DATA_1, value >> 16 & 0xffff);
|
||||
cci_write_register(CCI_REG_DATA_LENGTH, 2);
|
||||
cci_write_register(CCI_REG_COMMAND, CCI_CMD_OEM_SET_GPIO_MODE);
|
||||
cci_wait_busy_clear_check("CCI_CMD_OEM_SET_GPIO_MODE");
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Get the FLIR systems part number
|
||||
* - call with a 32-character buffer
|
||||
*/
|
||||
void cci_get_part_number(char* pn)
|
||||
{
|
||||
bool low_half = true;
|
||||
int i = 0;
|
||||
uint16_t cci_buf[16];
|
||||
|
||||
int t = 0; // maximum tick count
|
||||
|
||||
cci_get_reg(CCI_CMD_OEM_GET_PART_NUM, 16, cci_buf);
|
||||
|
||||
*pn = (char) (cci_buf[0] & 0xFF);
|
||||
while ((*pn != 0) && (i<16) && (t++ < CCI_MAX_WAIT_TICKS)) {
|
||||
low_half = !low_half;
|
||||
if (low_half) {
|
||||
*(++pn) = (char) (cci_buf[i] & 0xFF);
|
||||
} else {
|
||||
*(++pn) = (char) (cci_buf[i] >> 8);
|
||||
i++;
|
||||
}
|
||||
}
|
||||
*(++pn) = 0;
|
||||
}
|
||||
|
||||
|
||||
|
||||
//
|
||||
// Primitive access methods
|
||||
//
|
||||
|
||||
/**
|
||||
* Write a CCI register.
|
||||
*/
|
||||
static int cci_write_register(uint16_t reg, uint16_t value)
|
||||
{
|
||||
// Write the register address and value
|
||||
uint8_t write_buf[4] = {
|
||||
reg >> 8 & 0xff,
|
||||
reg & 0xff,
|
||||
value >> 8 & 0xff,
|
||||
value & 0xff
|
||||
};
|
||||
if (i2c_master_write_slave(CCI_ADDRESS, write_buf, sizeof(write_buf)) != ESP_OK) {
|
||||
printf("[CCI] Error: failed to write CCI register %02x with value %02x\n", reg, value);
|
||||
return -1;
|
||||
};
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Burst write a group of CCI data registers
|
||||
*/
|
||||
static int cci_write_burst(uint16_t start, uint16_t word_len, uint16_t* buf)
|
||||
{
|
||||
int i;
|
||||
|
||||
// Create the i2c transaction buffer
|
||||
burst_buf[0] = start >> 8;
|
||||
burst_buf[1] = start & 0xFF;
|
||||
for (i=1; i<=word_len; i++) {
|
||||
burst_buf[i*2] = *buf >> 8;
|
||||
burst_buf[i*2 + 1] = *buf++ & 0xFF;
|
||||
}
|
||||
|
||||
// Execute the burs
|
||||
if (i2c_master_write_slave(CCI_ADDRESS, burst_buf, word_len*2 + 2) != ESP_OK) {
|
||||
|
||||
printf("[CCI] Error: failed to burst write CCI register %02x with length %d\n", start, word_len);
|
||||
return -1;
|
||||
};
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Read a CCI register.
|
||||
*/
|
||||
static uint16_t cci_read_register(uint16_t reg)
|
||||
{
|
||||
uint8_t buf[2];
|
||||
|
||||
// Write the register address
|
||||
buf[0] = reg >> 8;
|
||||
buf[1] = reg & 0xff;
|
||||
|
||||
if (i2c_master_write_slave(CCI_ADDRESS, buf, sizeof(buf)) != ESP_OK) {
|
||||
printf("[CCI] Error: failed to write CCI register %02x\n", reg);
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Read
|
||||
if (i2c_master_read_slave(CCI_ADDRESS, buf, sizeof(buf)) != ESP_OK) {
|
||||
printf("[CCI] Error: failed to read from CCI register %02x\n", reg);
|
||||
}
|
||||
|
||||
return buf[0] << 8 | buf[1];
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Burst read a group of CCI data registers
|
||||
*/
|
||||
static int cci_read_burst(uint16_t start, uint16_t word_len, uint16_t* buf)
|
||||
{
|
||||
int i;
|
||||
|
||||
// Write the starting address
|
||||
burst_buf[0] = start >> 8;
|
||||
burst_buf[1] = start & 0xFF;
|
||||
if (i2c_master_write_slave(CCI_ADDRESS, burst_buf, 2) != ESP_OK) {
|
||||
printf("[CCI] Error: failed to write CCI register %02x\n", start);
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Read
|
||||
if (i2c_master_read_slave(CCI_ADDRESS, burst_buf, word_len*2) != ESP_OK) {
|
||||
printf("[CCI] Error: failed to burst read from CCI register %02x with length %d\n", start, word_len);
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Copy data out
|
||||
for (i=0; i<word_len; i++) {
|
||||
*buf++ = burst_buf[i*2] << 8 | burst_buf[i*2 + 1];
|
||||
}
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Wait for busy to be clear in the status register
|
||||
* Returns the 16-bit STATUS
|
||||
* Returns 0x00010000 if there is a communication failure
|
||||
*/
|
||||
static uint32_t cci_wait_busy_clear()
|
||||
{
|
||||
bool err = false;
|
||||
uint8_t buf[2] = {0x00, 0x07};
|
||||
|
||||
int t = 0; // maximum tick count
|
||||
|
||||
// Wait for booted, not busy
|
||||
while (((buf[1] & 0x07) != 0x06) && !err) {
|
||||
if (t++ >= CCI_MAX_WAIT_TICKS) {
|
||||
err = true;
|
||||
break;
|
||||
}
|
||||
|
||||
// Write STATUS register address
|
||||
buf[0] = 0x00;
|
||||
buf[1] = 0x02;
|
||||
|
||||
if (i2c_master_write_slave(CCI_ADDRESS, buf, sizeof(buf)) != ESP_OK) {
|
||||
printf("[CCI] Error: failed to set STATUS register\n");
|
||||
err = true;
|
||||
};
|
||||
|
||||
// Read register - low bits in buf[1]
|
||||
if (i2c_master_read_slave(CCI_ADDRESS, buf, sizeof(buf)) != ESP_OK) {
|
||||
printf("[CCI] Error: failed to read STATUS register\n");
|
||||
err = true;
|
||||
}
|
||||
}
|
||||
|
||||
if (err) {
|
||||
return 0x00010000;
|
||||
} else {
|
||||
return (buf[0] << 8) | buf[1];
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Wait for busy to be clear in the status register and check the result
|
||||
* printing an error if detected
|
||||
*/
|
||||
static void cci_wait_busy_clear_check(char* cmd)
|
||||
{
|
||||
int8_t response;
|
||||
uint32_t t32;
|
||||
|
||||
cci_last_status_error = false;
|
||||
|
||||
t32 = cci_wait_busy_clear();
|
||||
cci_last_status = t32 & 0xFFFF;
|
||||
if (t32 == 0x00010000) {
|
||||
printf("[CCI] Error: cmd: %s failed wait_busy_clear\n", cmd);
|
||||
cci_last_status_error = true;
|
||||
} else {
|
||||
response = (int8_t) ((t32 & 0x0000FF00) >> 8);
|
||||
if (response < 0) {
|
||||
printf("[CCI] Error: %s returned %d\n", cmd, response);
|
||||
}
|
||||
}
|
||||
}
|
216
src/lipton/cci.h
Normal file
216
src/lipton/cci.h
Normal file
@@ -0,0 +1,216 @@
|
||||
/*
|
||||
* Lepton CCI Module
|
||||
*
|
||||
* Contains the functions to configure the Lepton via I2C.
|
||||
*
|
||||
* Copyright 2020-2022 Dan Julio
|
||||
*
|
||||
* This file is part of tCam.
|
||||
*
|
||||
* tCam is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* tCam is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with tCam. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
|
||||
//
|
||||
// CCI constants
|
||||
//
|
||||
|
||||
// Device characteristics
|
||||
#define CCI_WORD_LENGTH 0x02
|
||||
#define CCI_ADDRESS 0x2A
|
||||
|
||||
// CCI register locations
|
||||
#define CCI_REG_STATUS 0x0002
|
||||
#define CCI_REG_COMMAND 0x0004
|
||||
#define CCI_REG_DATA_LENGTH 0x0006
|
||||
#define CCI_REG_DATA_0 0x0008
|
||||
#define CCI_REG_DATA_1 0x000A
|
||||
#define CCI_REG_DATA_2 0x000C
|
||||
#define CCI_REG_DATA_3 0x000E
|
||||
#define CCI_REG_DATA_4 0x0010
|
||||
#define CCI_REG_DATA_5 0x0012
|
||||
#define CCI_REG_DATA_6 0x0014
|
||||
#define CCI_REG_DATA_7 0x0016
|
||||
#define CCI_REG_DATA_8 0x0018
|
||||
#define CCI_REG_DATA_9 0x001A
|
||||
#define CCI_REG_DATA_10 0x001C
|
||||
#define CCI_REG_DATA_11 0x001E
|
||||
#define CCI_REG_DATA_12 0x0020
|
||||
#define CCI_REG_DATA_13 0x0022
|
||||
#define CCI_REG_DATA_14 0x0024
|
||||
#define CCI_REG_DATA_15 0x0026
|
||||
#define CCI_BLOCK_BUF_0 0xF800
|
||||
#define CCI_BLOCK_BUF_1 0xFC00
|
||||
|
||||
// Commands
|
||||
#define CCI_CMD_SYS_RUN_PING 0x0202
|
||||
#define CCI_CMD_SYS_GET_UPTIME 0x020C
|
||||
#define CCI_CMD_SYS_GET_AUX_TEMP 0x0210
|
||||
#define CCI_CMD_SYS_GET_FPA_TEMP 0x0214
|
||||
#define CCI_CMD_SYS_GET_TELEMETRY_ENABLE_STATE 0x0218
|
||||
#define CCI_CMD_SYS_SET_TELEMETRY_ENABLE_STATE 0x0219
|
||||
#define CCI_CMD_SYS_GET_TELEMETRY_LOCATION 0x021C
|
||||
#define CCI_CMD_SYS_SET_TELEMETRY_LOCATION 0x021D
|
||||
#define CCI_CMD_SYS_RUN_FFC 0x0242
|
||||
#define CCI_CMD_SYS_GET_GAIN_MODE 0x0248
|
||||
#define CCI_CMD_SYS_SET_GAIN_MODE 0x0249
|
||||
|
||||
#define CCI_CMD_RAD_GET_RADIOMETRY_ENABLE_STATE 0x4E10
|
||||
#define CCI_CMD_RAD_SET_RADIOMETRY_ENABLE_STATE 0x4E11
|
||||
#define CCI_CMD_RAD_GET_RADIOMETRY_FLUX_LINEAR_PARAMS 0x4EBC
|
||||
#define CCI_CMD_RAD_SET_RADIOMETRY_FLUX_LINEAR_PARAMS 0x4EBD
|
||||
#define CCI_CMD_RAD_GET_RADIOMETRY_TLINEAR_ENABLE_STATE 0x4EC0
|
||||
#define CCI_CMD_RAD_SET_RADIOMETRY_TLINEAR_ENABLE_STATE 0x4EC1
|
||||
#define CCI_CMD_RAD_GET_RADIOMETRY_TLINEAR_AUTO_RES 0x4EC8
|
||||
#define CCI_CMD_RAD_SET_RADIOMETRY_TLINEAR_AUTO_RES 0x4EC9
|
||||
#define CCI_CMD_RAD_GET_RADIOMETRY_SPOT_ROI 0x4ECC
|
||||
#define CCI_CMD_RAD_SET_RADIOMETRY_SPOT_ROI 0x4ECD
|
||||
|
||||
#define CCI_CMD_AGC_GET_AGC_ENABLE_STATE 0x0100
|
||||
#define CCI_CMD_AGC_SET_AGC_ENABLE_STATE 0x0101
|
||||
#define CCI_CMD_AGC_GET_CALC_ENABLE_STATE 0x0148
|
||||
#define CCI_CMD_AGC_SET_CALC_ENABLE_STATE 0x0149
|
||||
|
||||
#define CCI_CMD_OEM_RUN_REBOOT 0x4842
|
||||
|
||||
#define CCI_CMD_OEM_GET_GPIO_MODE 0x4854
|
||||
#define CCI_CMD_OEM_SET_GPIO_MODE 0x4855
|
||||
|
||||
#define CCI_CMD_OEM_GET_PART_NUM 0x481C
|
||||
|
||||
|
||||
//
|
||||
// Macros
|
||||
//
|
||||
#define WAIT_FOR_BUSY_DEASSERT() cci_wait_busy_clear()
|
||||
|
||||
|
||||
//
|
||||
// Enums
|
||||
//
|
||||
|
||||
// Telemetry Modes for use with CCI_CMD_SYS_SET_TELEMETRY_*
|
||||
typedef enum {
|
||||
CCI_TELEMETRY_DISABLED,
|
||||
CCI_TELEMETRY_ENABLED
|
||||
} cci_telemetry_enable_state_t;
|
||||
|
||||
typedef enum {
|
||||
CCI_TELEMETRY_LOCATION_HEADER,
|
||||
CCI_TELEMETRY_LOCATION_FOOTER
|
||||
} cci_telemetry_location_t;
|
||||
|
||||
// Gain Modes for use with CCI_CMD_SYS_SET_GAIN_MODE */
|
||||
typedef enum {
|
||||
LEP_SYS_GAIN_MODE_HIGH,
|
||||
LEP_SYS_GAIN_MODE_LOW,
|
||||
LEP_SYS_GAIN_MODE_AUTO
|
||||
} cc_gain_mode_t;
|
||||
|
||||
// Radiometry Modes for use with CCI_CMD_RAD_SET_RADIOMETRY*
|
||||
typedef enum {
|
||||
CCI_RADIOMETRY_DISABLED,
|
||||
CCI_RADIOMETRY_ENABLED
|
||||
} cci_radiometry_enable_state_t;
|
||||
|
||||
typedef enum {
|
||||
CCI_RADIOMETRY_TLINEAR_DISABLED,
|
||||
CCI_RADIOMETRY_TLINEAR_ENABLED
|
||||
} cci_radiometry_tlinear_enable_state_t;
|
||||
|
||||
typedef enum {
|
||||
CCI_RADIOMETRY_AUTO_RES_DISABLED,
|
||||
CCI_RADIOMETRY_AUTO_RES_ENABLED
|
||||
} cci_radiometry_tlinear_auto_res_state_t;
|
||||
|
||||
// AGC Modes for use with CCI_CMD_AGC_SET_AGC*
|
||||
typedef enum {
|
||||
CCI_AGC_DISABLED,
|
||||
CCI_AGC_ENABLED
|
||||
} cci_agc_enable_state_t;
|
||||
|
||||
// GPIO Modes for use with CCI_CMD_OEM_SET_GPIO_MODE*
|
||||
typedef enum {
|
||||
LEP_OEM_GPIO_MODE_GPIO = 0,
|
||||
LEP_OEM_GPIO_MODE_I2C_MASTER = 1,
|
||||
LEP_OEM_GPIO_MODE_SPI_MASTER_VLB_DATA = 2,
|
||||
LEP_OEM_GPIO_MODE_SPIO_MASTER_REG_DATA = 3,
|
||||
LEP_OEM_GPIO_MODE_SPI_SLAVE_VLB_DATA = 4,
|
||||
LEP_OEM_GPIO_MODE_VSYNC = 5
|
||||
} cci_gpio_mode_t;
|
||||
|
||||
// Radiometry Flux Linear Params
|
||||
typedef struct {
|
||||
uint16_t sceneEmissivity;
|
||||
uint16_t TBkgK;
|
||||
uint16_t tauWindow;
|
||||
uint16_t TWindowK;
|
||||
uint16_t tauAtm;
|
||||
uint16_t TAtmK;
|
||||
uint16_t reflWindow;
|
||||
uint16_t TReflK;
|
||||
} cci_rad_flux_linear_params_t;
|
||||
|
||||
|
||||
|
||||
//
|
||||
// CCI API
|
||||
//
|
||||
|
||||
// Generic access
|
||||
void cci_set_reg(uint16_t cmd, int len, uint16_t* buf);
|
||||
void cci_get_reg(uint16_t cmd, int len, uint16_t* buf);
|
||||
bool cci_command_success(uint16_t* status);
|
||||
|
||||
// Module: SYS
|
||||
uint32_t cci_run_ping();
|
||||
void cci_run_ffc();
|
||||
uint32_t cci_get_uptime();
|
||||
uint32_t cci_get_aux_temp();
|
||||
uint32_t cci_get_fpa_temp();
|
||||
void cci_set_telemetry_enable_state(cci_telemetry_enable_state_t state);
|
||||
uint32_t cci_get_telemetry_enable_state();
|
||||
void cci_set_telemetry_location(cci_telemetry_location_t location);
|
||||
uint32_t cci_get_telemetry_location();
|
||||
void cci_set_gain_mode(cc_gain_mode_t mode);
|
||||
uint32_t cci_get_gain_mode();
|
||||
|
||||
// Module: RAD
|
||||
void cci_set_radiometry_enable_state(cci_radiometry_enable_state_t state);
|
||||
uint32_t cci_get_radiometry_enable_state();
|
||||
void cci_set_radiometry_flux_linear_params(cci_rad_flux_linear_params_t* params);
|
||||
bool cci_get_radiometry_flux_linear_params(cci_rad_flux_linear_params_t* params);
|
||||
void cci_set_radiometry_tlinear_enable_state(cci_radiometry_tlinear_enable_state_t state);
|
||||
uint32_t cci_get_radiometry_tlinear_enable_state();
|
||||
void cci_set_radiometry_tlinear_auto_res(cci_radiometry_tlinear_auto_res_state_t state);
|
||||
uint32_t cci_get_radiometry_tlinear_auto_res();
|
||||
void cci_set_radiometry_spotmeter(uint16_t r1, uint16_t c1, uint16_t r2, uint16_t c2);
|
||||
bool cci_get_radiometry_spotmeter(uint16_t* r1, uint16_t* c1, uint16_t* r2, uint16_t* c2);
|
||||
|
||||
// Module: AGC
|
||||
void cci_set_agc_enable_state(cci_agc_enable_state_t state);
|
||||
uint32_t cci_get_agc_enable_state();
|
||||
void cci_set_agc_calc_enable_state(cci_agc_enable_state_t state);
|
||||
uint32_t cci_get_agc_calc_enable_state();
|
||||
|
||||
// Module: OEM
|
||||
void cc_run_oem_reboot();
|
||||
uint32_t cci_get_gpio_mode();
|
||||
void cci_set_gpio_mode(cci_gpio_mode_t mode);
|
||||
void cci_get_part_number(char* pn);
|
110
src/lipton/i2c.cpp
Normal file
110
src/lipton/i2c.cpp
Normal file
@@ -0,0 +1,110 @@
|
||||
/*
|
||||
* I2C Module
|
||||
*
|
||||
* Provides I2C Access routines for other modules/tasks. Provides a locking mechanism
|
||||
* since the underlying ESP IDF routines are not thread safe.
|
||||
*
|
||||
* Copyright 2020-2022 Dan Julio
|
||||
*
|
||||
* This file is part of tCam.
|
||||
*
|
||||
* tCam is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* tCam is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with tCam. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
// #include "system_config.h"
|
||||
#include "i2c.h"
|
||||
#include "driver/i2c.h"
|
||||
#include "lepton_system.h"
|
||||
// #include "freertos/FreeRTOS.h"
|
||||
// #include "freertos/semphr.h"
|
||||
|
||||
|
||||
//
|
||||
// I2C API
|
||||
//
|
||||
|
||||
/**
|
||||
* i2c master initialization
|
||||
*/
|
||||
esp_err_t i2c_master_init(int scl_pin, int sda_pin)
|
||||
{
|
||||
int i2c_master_port = I2C_MASTER_NUM;
|
||||
i2c_config_t conf;
|
||||
|
||||
// Configure the I2C controller in master mode using the pins provided
|
||||
conf.mode = I2C_MODE_MASTER;
|
||||
conf.sda_io_num = sda_pin;
|
||||
conf.sda_pullup_en = GPIO_PULLUP_ENABLE;
|
||||
conf.scl_io_num = scl_pin;
|
||||
conf.scl_pullup_en = GPIO_PULLUP_ENABLE;
|
||||
conf.master.clk_speed = I2C_MASTER_FREQ_HZ;
|
||||
conf.clk_flags = 0;
|
||||
esp_err_t err = i2c_param_config((i2c_port_t)i2c_master_port, &conf);
|
||||
if (err != ESP_OK) {
|
||||
return err;
|
||||
}
|
||||
|
||||
// Install the I2C driver
|
||||
return i2c_driver_install((i2c_port_t)i2c_master_port, conf.mode,
|
||||
I2C_MASTER_RX_BUF_LEN,
|
||||
I2C_MASTER_TX_BUF_LEN, 0);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Read esp-i2c-slave
|
||||
*
|
||||
* _______________________________________________________________________________________
|
||||
* | start | slave_addr + rd_bit +ack | read n-1 bytes + ack | read 1 byte + nack | stop |
|
||||
* --------|--------------------------|----------------------|--------------------|------|
|
||||
*
|
||||
*/
|
||||
esp_err_t i2c_master_read_slave(uint8_t addr7, uint8_t *data_rd, size_t size)
|
||||
{
|
||||
if (size == 0) {
|
||||
return ESP_OK;
|
||||
}
|
||||
i2c_cmd_handle_t cmd = i2c_cmd_link_create();
|
||||
i2c_master_start(cmd);
|
||||
i2c_master_write_byte(cmd, (addr7 << 1) | I2C_MASTER_READ, ACK_CHECK_EN);
|
||||
if (size > 1) {
|
||||
i2c_master_read(cmd, data_rd, size - 1, ACK_VAL);
|
||||
}
|
||||
i2c_master_read_byte(cmd, data_rd + size - 1, NACK_VAL);
|
||||
i2c_master_stop(cmd);
|
||||
esp_err_t ret = i2c_master_cmd_begin((i2c_port_t)I2C_MODE_MASTER, cmd, 1000 / portTICK_RATE_MS);
|
||||
i2c_cmd_link_delete(cmd);
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Write esp-i2c-slave
|
||||
*
|
||||
* ___________________________________________________________________
|
||||
* | start | slave_addr + wr_bit + ack | write n bytes + ack | stop |
|
||||
* --------|---------------------------|----------------------|------|
|
||||
*
|
||||
*/
|
||||
esp_err_t i2c_master_write_slave(uint8_t addr7, uint8_t *data_wr, size_t size)
|
||||
{
|
||||
i2c_cmd_handle_t cmd = i2c_cmd_link_create();
|
||||
i2c_master_start(cmd);
|
||||
i2c_master_write_byte(cmd, (addr7 << 1) | I2C_MASTER_WRITE, ACK_CHECK_EN);
|
||||
i2c_master_write(cmd, data_wr, size, ACK_CHECK_EN);
|
||||
i2c_master_stop(cmd);
|
||||
esp_err_t ret = i2c_master_cmd_begin((i2c_port_t)I2C_MODE_MASTER, cmd, 1000 / portTICK_RATE_MS);
|
||||
i2c_cmd_link_delete(cmd);
|
||||
return ret;
|
||||
}
|
50
src/lipton/i2c.h
Normal file
50
src/lipton/i2c.h
Normal file
@@ -0,0 +1,50 @@
|
||||
/*
|
||||
* I2C Module
|
||||
*
|
||||
* Provides I2C Access routines for other modules/tasks. Provides a locking mechanism
|
||||
* since the underlying ESP IDF routines are not thread safe.
|
||||
*
|
||||
* Copyright 2020-2022 Dan Julio
|
||||
*
|
||||
* This file is part of tCam.
|
||||
*
|
||||
* tCam is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* tCam is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with tCam. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
#include "esp_system.h"
|
||||
#include "driver/i2c.h"
|
||||
|
||||
//
|
||||
// I2C constants
|
||||
//
|
||||
|
||||
// Slave buffer size (not used)
|
||||
#define I2C_MASTER_TX_BUF_LEN 0
|
||||
#define I2C_MASTER_RX_BUF_LEN 0
|
||||
|
||||
#define ACK_CHECK_EN 0x1
|
||||
#define ACK_CHECK_DIS 0x0
|
||||
#define ACK_VAL (i2c_ack_type_t)0x0
|
||||
#define NACK_VAL (i2c_ack_type_t)0x1
|
||||
|
||||
|
||||
//
|
||||
// I2C API
|
||||
//
|
||||
esp_err_t i2c_master_init(int scl_pin, int sda_pin);
|
||||
esp_err_t i2c_master_read_slave(uint8_t addr7, uint8_t *data_rd, size_t size);
|
||||
esp_err_t i2c_master_write_slave(uint8_t addr7, uint8_t *data_wr, size_t size);
|
79
src/lipton/lepton_system.cpp
Normal file
79
src/lipton/lepton_system.cpp
Normal file
@@ -0,0 +1,79 @@
|
||||
#include "esp_system.h"
|
||||
#include <stdlib.h>
|
||||
#include "driver/spi_master.h"
|
||||
#include "driver/spi_slave.h"
|
||||
#include "lepton_system.h"
|
||||
#include "lepton_utilities.h"
|
||||
#include "i2c.h"
|
||||
#include "vospi.h"
|
||||
#include <cstring>
|
||||
#include <Arduino.h>
|
||||
|
||||
|
||||
// lepton image and telem buffer
|
||||
lep_buffer_t rsp_lep_buffer;
|
||||
|
||||
/**
|
||||
* Initialize the ESP32 GPIO and internal peripherals
|
||||
*/
|
||||
bool lepton_io_init()
|
||||
{
|
||||
esp_err_t ret;
|
||||
spi_bus_config_t spi_buscfg;
|
||||
|
||||
printf("[LEP SYS] Lepton I/O Initialization\n");
|
||||
|
||||
// Attempt to initialize the I2C Master
|
||||
ret = i2c_master_init(I2C_MASTER_SCL_PIN, I2C_MASTER_SDA_PIN);
|
||||
if (ret != ESP_OK) {
|
||||
printf("[LEP SYS] Error: I2C Master initialization failed\n");
|
||||
return false;
|
||||
}
|
||||
|
||||
// Attempt to initialize the SPI Master used by the lep_task
|
||||
memset(&spi_buscfg, 0, sizeof(spi_bus_config_t));
|
||||
spi_buscfg.miso_io_num=LEP_MISO_PIN;
|
||||
spi_buscfg.mosi_io_num=-1;
|
||||
spi_buscfg.sclk_io_num=LEP_SCK_PIN;
|
||||
spi_buscfg.max_transfer_sz=LEP_PKT_LENGTH;
|
||||
spi_buscfg.quadwp_io_num=-1;
|
||||
spi_buscfg.quadhd_io_num=-1;
|
||||
|
||||
if (spi_bus_initialize(LEP_SPI_HOST, &spi_buscfg, LEP_DMA_NUM) != ESP_OK) {
|
||||
printf("[LEP SYS] Error: Lepton SPI initialization failed\n");
|
||||
return false;
|
||||
}
|
||||
|
||||
// initialize GPIO pins
|
||||
pinMode(LEP_VSYNC_PIN, INPUT);
|
||||
pinMode(LEP_RESET_PIN, OUTPUT);
|
||||
digitalWrite(LEP_RESET_PIN, LEP_RESET_ON);
|
||||
delay(10);
|
||||
digitalWrite(LEP_RESET_PIN, LEP_RESET_OFF);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Allocate lepton buffers on heap
|
||||
*/
|
||||
bool lepton_buffer_init()
|
||||
{
|
||||
printf("[LEP SYS] Buffer Allocation\n");
|
||||
|
||||
// Allocate the LEP/RSP task lepton frame and telemetry ping-pong buffers
|
||||
rsp_lep_buffer.lep_bufferP = (uint16_t*)malloc(LEP_NUM_PIXELS*sizeof(uint16_t));
|
||||
if (rsp_lep_buffer.lep_bufferP == NULL) {
|
||||
printf("[LEP SYS] Error: malloc RSP lepton shared image buffer failed\n");
|
||||
return false;
|
||||
}
|
||||
|
||||
rsp_lep_buffer.lep_telemP = (uint16_t*)malloc(LEP_TEL_WORDS*sizeof(uint16_t));
|
||||
if (rsp_lep_buffer.lep_telemP == NULL) {
|
||||
printf("[LEP SYS] Error: malloc RSP lepton shared telemetry buffer failed\n");
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
55
src/lipton/lepton_system.h
Normal file
55
src/lipton/lepton_system.h
Normal file
@@ -0,0 +1,55 @@
|
||||
#pragma once
|
||||
|
||||
//
|
||||
// Hardware Configuration
|
||||
//
|
||||
// ESP // LEPTON
|
||||
// #define LEP_SCK_PIN 14 // SPI_CLK 18
|
||||
// #define LEP_CSN_PIN 15 // SPI_CS 10
|
||||
// #define LEP_VSYNC_PIN 13 // GPIO3/VSYNC 15
|
||||
// #define LEP_MISO_PIN 12 // SPI_MISO 12
|
||||
// #define LEP_RESET_PIN 27 // RESET_L 17
|
||||
|
||||
// #define I2C_MASTER_SDA_PIN 21 // SDA 5
|
||||
// #define I2C_MASTER_SCL_PIN 22 // SCL 8
|
||||
|
||||
#define LEP_SCK_PIN 14 // SPI_CLK 18
|
||||
#define LEP_CSN_PIN 15 // SPI_CS 10
|
||||
#define LEP_VSYNC_PIN 13 // GPIO3/VSYNC 15
|
||||
#define LEP_MISO_PIN 12 // SPI_MISO 12
|
||||
#define LEP_RESET_PIN 16 // RESET_L 17
|
||||
|
||||
#define I2C_MASTER_SDA_PIN 2 // SDA 5
|
||||
#define I2C_MASTER_SCL_PIN 4 // SCL 8
|
||||
|
||||
// I2C
|
||||
#define I2C_MASTER_NUM 1
|
||||
#define I2C_MASTER_FREQ_HZ 100000
|
||||
|
||||
// SPI
|
||||
// Lepton uses HSPI (no MOSI)
|
||||
// Host SPI Slave uses VSPI (no MOSI)
|
||||
#define LEP_SPI_HOST HSPI_HOST
|
||||
#define LEP_DMA_NUM 2
|
||||
#define LEP_SPI_FREQ_HZ 16000000
|
||||
|
||||
|
||||
//
|
||||
// Lepton Buffers Typedef
|
||||
//
|
||||
typedef struct
|
||||
{
|
||||
bool telem_valid;
|
||||
uint16_t lep_min_val;
|
||||
uint16_t lep_max_val;
|
||||
uint16_t *lep_bufferP;
|
||||
uint16_t *lep_telemP;
|
||||
} lep_buffer_t;
|
||||
|
||||
extern lep_buffer_t rsp_lep_buffer;
|
||||
|
||||
//
|
||||
// System init functions
|
||||
//
|
||||
bool lepton_io_init();
|
||||
bool lepton_buffer_init();
|
287
src/lipton/lepton_utilities.cpp
Normal file
287
src/lipton/lepton_utilities.cpp
Normal file
@@ -0,0 +1,287 @@
|
||||
/*
|
||||
* Lepton related utilities
|
||||
*
|
||||
* Contains utility and access functions for the Lepton.
|
||||
*
|
||||
* Note: I noticed that on occasion, the first time some commands run on the lepton
|
||||
* will fail either silently or with an error response code. The access routines in
|
||||
* this module attempt to detect and retry the commands if necessary.
|
||||
*
|
||||
* Copyright 2020 Dan Julio
|
||||
*
|
||||
* This file is part of tCam.
|
||||
*
|
||||
* tCam is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* tCam is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with tCam. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#include "lepton_utilities.h"
|
||||
#include "cci.h"
|
||||
#include "i2c.h"
|
||||
#include "esp_system.h"
|
||||
#include "vospi.h"
|
||||
#include <string.h>
|
||||
#include <Arduino.h>
|
||||
|
||||
|
||||
static bool lep_is_radiometric = false;
|
||||
static int lep_type;
|
||||
|
||||
// default lepton config
|
||||
lepton_config_t LEP_CONFIG = {
|
||||
.agc_set_enabled = false,
|
||||
.emissivity = 100,
|
||||
.gain_mode = LEP_GAIN_HIGH
|
||||
};
|
||||
|
||||
//
|
||||
// Lepton Utilities API
|
||||
//
|
||||
bool lepton_init()
|
||||
{
|
||||
char pn[33];
|
||||
uint32_t val, rsp;
|
||||
lepton_config_t* lep_stP = &LEP_CONFIG;
|
||||
|
||||
// Attempt to ping the Lepton to validate communication
|
||||
// If this is successful, we assume further communication will be successful
|
||||
rsp = cci_run_ping();
|
||||
if (rsp != 0) {
|
||||
printf("[LEP UTIL] Error: Lepton communication failed (%d)\n", rsp);
|
||||
return false;
|
||||
}
|
||||
|
||||
// Get the Lepton type (part number) to determine if it's a Lepton 3.0 or 3.5
|
||||
cci_get_part_number(pn);
|
||||
printf("[LEP UTIL] Found Lepton, part number: %s\n", pn);
|
||||
if (strncmp(pn, "500-0771-01", 32) == 0) {
|
||||
printf(" Radiometric Lepton 3.5\n");
|
||||
lep_is_radiometric = true;
|
||||
lep_type = LEP_TYPE_3_5;
|
||||
} else if (strncmp(pn, "500-0758-99", 32) == 0) {
|
||||
printf(" Radiometric Lepton 3.1\n");
|
||||
lep_is_radiometric = true;
|
||||
lep_type = LEP_TYPE_3_1;
|
||||
} else if (strncmp(pn, "500-0726-01", 32) == 0) {
|
||||
printf(" Non-radiometric Lepton 3.0\n");
|
||||
lep_is_radiometric = false;
|
||||
lep_type = LEP_TYPE_3_0;
|
||||
} else {
|
||||
printf(" Unsupported Lepton");
|
||||
lep_is_radiometric = true;
|
||||
lep_type = LEP_TYPE_UNK;
|
||||
}
|
||||
|
||||
if (lep_is_radiometric) {
|
||||
// Configure Radiometry for TLinear enabled, auto-resolution
|
||||
cci_set_radiometry_enable_state(CCI_RADIOMETRY_ENABLED);
|
||||
rsp = cci_get_radiometry_enable_state();
|
||||
printf("[LEP UTIL] Lepton Radiometry = %d\n", rsp);
|
||||
if (rsp != CCI_RADIOMETRY_ENABLED) {
|
||||
// Make one more effort
|
||||
delay(10);
|
||||
printf("[LEP UTIL] Retry Set Lepton Radiometry\n");
|
||||
cci_set_radiometry_enable_state(CCI_RADIOMETRY_ENABLED);
|
||||
rsp = cci_get_radiometry_enable_state();
|
||||
printf("[LEP UTIL] Lepton Radiometry = %d\n", rsp);
|
||||
if (rsp != CCI_RADIOMETRY_ENABLED) {
|
||||
printf("[LEP UTIL] Error: Lepton communication failed (%d)\n", rsp);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// TLinear depends on AGC
|
||||
val = (lep_stP->agc_set_enabled) ? CCI_RADIOMETRY_TLINEAR_DISABLED : CCI_RADIOMETRY_TLINEAR_ENABLED;
|
||||
cci_set_radiometry_tlinear_enable_state((cci_radiometry_tlinear_enable_state_t)val);
|
||||
rsp = cci_get_radiometry_tlinear_enable_state();
|
||||
printf("[LEP UTIL] Lepton Radiometry TLinear = %d\n", rsp);
|
||||
if (rsp != val) {
|
||||
printf("[LEP UTIL] Error: Lepton communication failed (%d)\n", rsp);
|
||||
return false;
|
||||
}
|
||||
|
||||
cci_set_radiometry_tlinear_auto_res(CCI_RADIOMETRY_AUTO_RES_ENABLED);
|
||||
rsp = cci_get_radiometry_tlinear_auto_res();
|
||||
printf("[LEP UTIL] Lepton Radiometry Auto Resolution = %d\n", rsp);
|
||||
if (rsp != CCI_RADIOMETRY_AUTO_RES_ENABLED) {
|
||||
printf("[LEP UTIL] Error: Lepton communication failed (%d)\n", rsp);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// Enable AGC calcs for a smooth transition between modes
|
||||
cci_set_agc_calc_enable_state(CCI_AGC_ENABLED);
|
||||
rsp = cci_get_agc_calc_enable_state();
|
||||
printf("[LEP UTIL] Lepton AGC Calcs = %d\n", rsp);
|
||||
if (rsp != CCI_AGC_ENABLED) {
|
||||
printf("[LEP UTIL] Error: Lepton communication failed (%d)\n", rsp);
|
||||
return false;
|
||||
}
|
||||
|
||||
// AGC
|
||||
val = (lep_stP->agc_set_enabled) ? CCI_AGC_ENABLED : CCI_AGC_DISABLED;
|
||||
cci_set_agc_enable_state((cci_agc_enable_state_t)val);
|
||||
rsp = cci_get_agc_enable_state();
|
||||
printf("[LEP UTIL] Lepton AGC = %d\n", rsp);
|
||||
if (rsp != val) {
|
||||
printf("[LEP UTIL] Error: Lepton communication failed (%d)\n", rsp);
|
||||
return false;
|
||||
}
|
||||
|
||||
// Enable telemetry
|
||||
cci_set_telemetry_enable_state(CCI_TELEMETRY_ENABLED);
|
||||
rsp = cci_get_telemetry_enable_state();
|
||||
printf("[LEP UTIL] Lepton Telemetry = %d\n", rsp);
|
||||
if (rsp != CCI_TELEMETRY_ENABLED) {
|
||||
printf("[LEP UTIL] Error: Lepton communication failed (%d)\n", rsp);
|
||||
return false;
|
||||
}
|
||||
vospi_include_telem(true);
|
||||
|
||||
// GAIN
|
||||
switch (lep_stP->gain_mode) {
|
||||
case LEP_GAIN_HIGH:
|
||||
val = LEP_SYS_GAIN_MODE_HIGH;
|
||||
break;
|
||||
case LEP_GAIN_LOW:
|
||||
val = LEP_SYS_GAIN_MODE_LOW;
|
||||
break;
|
||||
default:
|
||||
val = LEP_SYS_GAIN_MODE_AUTO;
|
||||
}
|
||||
cci_set_gain_mode((cc_gain_mode_t)val);
|
||||
rsp = cci_get_gain_mode();
|
||||
printf("[LEP UTIL] Lepton Gain Mode = %d\n", rsp);
|
||||
if (rsp != val) {
|
||||
printf("[LEP UTIL] Error: Lepton communication failed (%d)\n", rsp);
|
||||
return false;
|
||||
}
|
||||
|
||||
// Emissivity
|
||||
if (lep_is_radiometric) {
|
||||
lepton_emissivity(lep_stP->emissivity);
|
||||
printf("[LEP UTIL] Lepton Emissivity = %d%%\n", lep_stP->emissivity);
|
||||
}
|
||||
|
||||
// Finally enable VSYNC on Lepton GPIO3
|
||||
cci_set_gpio_mode(LEP_OEM_GPIO_MODE_VSYNC);
|
||||
rsp = cci_get_gpio_mode();
|
||||
printf("[LEP UTIL] Lepton GPIO Mode = %d\n", rsp);
|
||||
if (rsp != LEP_OEM_GPIO_MODE_VSYNC) {
|
||||
printf("[LEP UTIL] Error: Lepton communication failed (%d)\n", rsp);
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
bool lepton_is_radiometric()
|
||||
{
|
||||
return lep_is_radiometric;
|
||||
}
|
||||
|
||||
|
||||
int lepton_get_model()
|
||||
{
|
||||
return lep_type;
|
||||
}
|
||||
|
||||
|
||||
void lepton_agc(bool en)
|
||||
{
|
||||
if (en) {
|
||||
if (lep_is_radiometric) {
|
||||
cci_set_radiometry_tlinear_enable_state(CCI_RADIOMETRY_TLINEAR_DISABLED);
|
||||
}
|
||||
cci_set_agc_enable_state(CCI_AGC_ENABLED);
|
||||
} else {
|
||||
if (lep_is_radiometric) {
|
||||
cci_set_radiometry_tlinear_enable_state(CCI_RADIOMETRY_TLINEAR_ENABLED);
|
||||
}
|
||||
cci_set_agc_enable_state(CCI_AGC_DISABLED);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void lepton_ffc()
|
||||
{
|
||||
cci_run_ffc();
|
||||
}
|
||||
|
||||
|
||||
void lepton_gain_mode(uint8_t mode)
|
||||
{
|
||||
cc_gain_mode_t gain_mode;
|
||||
|
||||
if (lep_is_radiometric) {
|
||||
switch (mode) {
|
||||
case LEP_GAIN_HIGH:
|
||||
gain_mode = LEP_SYS_GAIN_MODE_HIGH;
|
||||
break;
|
||||
case LEP_GAIN_LOW:
|
||||
gain_mode = LEP_SYS_GAIN_MODE_LOW;
|
||||
break;
|
||||
default:
|
||||
gain_mode = LEP_SYS_GAIN_MODE_AUTO;
|
||||
}
|
||||
cci_set_gain_mode(gain_mode);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void lepton_spotmeter(uint16_t r1, uint16_t c1, uint16_t r2, uint16_t c2)
|
||||
{
|
||||
if (lep_is_radiometric) {
|
||||
cci_set_radiometry_spotmeter(r1, c1, r2, c2);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void lepton_emissivity(uint16_t e)
|
||||
{
|
||||
cci_rad_flux_linear_params_t set_flux_values;
|
||||
|
||||
if (lep_is_radiometric) {
|
||||
// Scale percentage e into Lepton scene emissivity values (1-100% -> 82-8192)
|
||||
if (e < 1) e = 1;
|
||||
if (e > 100) e = 100;
|
||||
set_flux_values.sceneEmissivity = e * 8192 / 100;
|
||||
|
||||
// Set default (no lens) values for the remaining parameters
|
||||
set_flux_values.TBkgK = 29515;
|
||||
set_flux_values.tauWindow = 8192;
|
||||
set_flux_values.TWindowK = 29515;
|
||||
set_flux_values.tauAtm = 8192;
|
||||
set_flux_values.TAtmK = 29515;
|
||||
set_flux_values.reflWindow = 0;
|
||||
set_flux_values.TReflK = 29515;
|
||||
|
||||
cci_set_radiometry_flux_linear_params(&set_flux_values);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
uint32_t lepton_get_tel_status(uint16_t* tel_buf)
|
||||
{
|
||||
return (tel_buf[LEP_TEL_STATUS_HIGH] << 16) | tel_buf[LEP_TEL_STATUS_LOW];
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Convert a temperature reading from the lepton (in units of K * 100) to C
|
||||
*/
|
||||
float lepton_kelvin_to_C(uint32_t k, float lep_res)
|
||||
{
|
||||
return (((float) k) * lep_res) - 273.15;
|
||||
}
|
181
src/lipton/lepton_utilities.h
Normal file
181
src/lipton/lepton_utilities.h
Normal file
@@ -0,0 +1,181 @@
|
||||
/*
|
||||
* Lepton related utilities
|
||||
*
|
||||
* Contains utility and access functions for the Lepton.
|
||||
*
|
||||
* Copyright 2020 Dan Julio
|
||||
*
|
||||
* This file is part of tCam.
|
||||
*
|
||||
* tCam is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* tCam is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with tCam. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
//
|
||||
// Lepton Utilities Constants
|
||||
//
|
||||
|
||||
//
|
||||
// Telemetry words
|
||||
//
|
||||
// From Row A (words 0-79)
|
||||
#define LEP_TEL_REV 0
|
||||
#define LEP_TEL_TC_LOW 1
|
||||
#define LEP_TEL_TC_HIGH 2
|
||||
#define LEP_TEL_STATUS_LOW 3
|
||||
#define LEP_TEL_STATUS_HIGH 4
|
||||
#define LEP_TEL_SN_0 5
|
||||
#define LEP_TEL_SN_1 6
|
||||
#define LEP_TEL_SN_2 7
|
||||
#define LEP_TEL_SN_3 8
|
||||
#define LEP_TEL_SN_4 9
|
||||
#define LEP_TEL_SN_5 10
|
||||
#define LEP_TEL_SN_6 11
|
||||
#define LEP_TEL_SN_7 12
|
||||
#define LEP_TEL_REV_0 13
|
||||
#define LEP_TEL_REV_1 14
|
||||
#define LEP_TEL_REV_2 15
|
||||
#define LEP_TEL_REV_3 16
|
||||
#define LEP_TEL_FC_LOW 20
|
||||
#define LEP_TEL_FC_HIGH 21
|
||||
#define LEP_TEL_FRAME_MEAN 22
|
||||
#define LEP_TEL_FPA_T_CNT 23
|
||||
#define LEP_TEL_FPA_T_K100 24
|
||||
#define LEP_TEL_HSE_T_CNT 25
|
||||
#define LEP_TEL_HSE_T_K100 26
|
||||
#define LEP_TEL_LAST_FPA_T 29
|
||||
#define LEP_TEL_LAST_TC_LOW 30
|
||||
#define LEP_TEL_LAST_TC_HIGH 31
|
||||
#define LEP_TEL_LAST_HST_T 32
|
||||
#define LEP_TEL_AGC_ROI_0 34
|
||||
#define LEP_TEL_AGC_ROI_1 35
|
||||
#define LEP_TEL_AGC_ROI_2 36
|
||||
#define LEP_TEL_AGC_ROI_3 37
|
||||
#define LEP_TEL_AGC_CL_HIGH 38
|
||||
#define LEP_TEL_AGC_CL_LOW 39
|
||||
#define LEP_TEL_VID_FMT_LOW 72
|
||||
#define LEP_TEL_VID_FMT_HIGH 73
|
||||
#define LEP_TEL_FFC_FR_LOG2 74
|
||||
|
||||
// From Row B (words 80-159)
|
||||
#define LEP_TEL_EMISSIVITY 99
|
||||
#define LEP_TEL_BG_T_K100 100
|
||||
#define LEP_TEL_ATM_TRANS 101
|
||||
#define LEP_TEL_ATM_T_K100 102
|
||||
#define LEP_TEL_WND_TRANS 103
|
||||
#define LEP_TEL_WND_REFL 104
|
||||
#define LEP_TEL_WND_T_K100 105
|
||||
#define LEP_TEL_WND_REFL_T_K100 106
|
||||
|
||||
// From Row C (words 160-239)
|
||||
#define LEP_TEL_GAIN_MODE 165
|
||||
#define LEP_TEL_EFF_GAIN_MODE 166
|
||||
#define LEP_TEL_GAIN_MODE_DES 167
|
||||
#define LEP_TEL_GAIN_TH_H2LC 168
|
||||
#define LEP_TEL_GAIN_TH_L2HC 169
|
||||
#define LEP_TEL_GAIN_TH_H2LK 170
|
||||
#define LEP_TEL_GAIN_TH_L2HK 171
|
||||
#define LEP_TEL_GAIN_POP_H2L 174
|
||||
#define LEP_TEL_GAIN_POP_L2H 175
|
||||
#define LEP_TEL_GAIN_MODE_ROI_0 182
|
||||
#define LEP_TEL_GAIN_MODE_ROI_1 183
|
||||
#define LEP_TEL_GAIN_MODE_ROI_2 184
|
||||
#define LEP_TEL_GAIN_MODE_ROI_3 185
|
||||
#define LEP_TEL_TLIN_ENABLE 208
|
||||
#define LEP_TEL_TLIN_RES 209
|
||||
#define LEP_TEL_SPOT_MEAN 210
|
||||
#define LEP_TEL_SPOT_MAX 211
|
||||
#define LEP_TEL_SPOT_MIN 212
|
||||
#define LEP_TEL_SPOT_POP 213
|
||||
#define LEP_TEL_SPOT_Y1 214
|
||||
#define LEP_TEL_SPOT_X1 215
|
||||
#define LEP_TEL_SPOT_Y2 216
|
||||
#define LEP_TEL_SPOT_X2 217
|
||||
|
||||
|
||||
|
||||
//
|
||||
// Telemetry Status DWORD mask
|
||||
//
|
||||
#define LEP_STATUS_FFC_DESIRED 0x00000008
|
||||
#define LEP_STATUS_FFC_STATE 0x00000030
|
||||
#define LEP_STATUS_AGC_STATE 0x00001000
|
||||
#define LEP_STATUS_SHTR_LO 0x00008000
|
||||
#define LEP_STATUS_OT_IMM 0x00100000
|
||||
|
||||
//
|
||||
// Telemetry Status FFC State
|
||||
//
|
||||
#define LEP_FFC_STATE_IDLE 0x00000000
|
||||
#define LEP_FFC_STATE_IMM 0x00000010
|
||||
#define LEP_FFC_STATE_RUN 0x00000020
|
||||
#define LEP_FFC_STATE_CMPL 0x00000030
|
||||
|
||||
//
|
||||
// Lepton Types
|
||||
//
|
||||
#define LEP_TYPE_3_5 0
|
||||
#define LEP_TYPE_3_0 1
|
||||
#define LEP_TYPE_3_1 2
|
||||
#define LEP_TYPE_UNK 3
|
||||
|
||||
//
|
||||
// Lepton Gain mode
|
||||
//
|
||||
#define LEP_GAIN_HIGH 0
|
||||
#define LEP_GAIN_LOW 1
|
||||
#define LEP_GAIN_AUTO 2
|
||||
|
||||
//
|
||||
// Lepton Reset mode
|
||||
//
|
||||
#define LEP_RESET_ON 0
|
||||
#define LEP_RESET_OFF 1
|
||||
|
||||
//
|
||||
// Lepton Power mode
|
||||
//
|
||||
#define LEP_POWER_ON 1
|
||||
#define LEP_POWER_OFF 0
|
||||
|
||||
//
|
||||
// Lepton configuration
|
||||
//
|
||||
typedef struct {
|
||||
bool agc_set_enabled; // Set when agc_enabled
|
||||
int emissivity; // Integer percent 1 - 100
|
||||
int gain_mode; // LEP_GAIN_HIGH / LEP_GAIN_LOW / LEP_GAIN_AUTO
|
||||
} lepton_config_t;
|
||||
|
||||
extern lepton_config_t LEP_CONFIG;
|
||||
|
||||
//
|
||||
// Lepton Utilities API
|
||||
//
|
||||
bool lepton_init();
|
||||
bool lepton_is_radiometric();
|
||||
int lepton_get_model();
|
||||
void lepton_agc(bool en);
|
||||
void lepton_ffc();
|
||||
void lepton_gain_mode(uint8_t mode);
|
||||
void lepton_spotmeter(uint16_t r1, uint16_t c1, uint16_t r2, uint16_t c2);
|
||||
void lepton_emissivity(uint16_t e);
|
||||
|
||||
uint32_t lepton_get_tel_status(uint16_t* tel_buf);
|
||||
|
||||
float lepton_kelvin_to_C(uint32_t k, float lep_res);
|
320
src/lipton/vospi.cpp
Normal file
320
src/lipton/vospi.cpp
Normal file
@@ -0,0 +1,320 @@
|
||||
/*
|
||||
* Lepton VoSPI Module
|
||||
*
|
||||
* Contains the functions to get frames from a Lepton 3.5 via its SPI port.
|
||||
* Optionally supports collecting telemetry when enabled as a footer (does not
|
||||
* support telemetry enabled as a header).
|
||||
*
|
||||
* Copyright 2020-2022 Dan Julio
|
||||
*
|
||||
* This file is part of tCam.
|
||||
*
|
||||
* tCam is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* tCam is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with tCam. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#include <stdint.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include "esp_system.h"
|
||||
#include "esp_timer.h"
|
||||
#include "driver/spi_master.h"
|
||||
#include "lepton_system.h"
|
||||
#include "vospi.h"
|
||||
|
||||
//
|
||||
// VoSPI Variables
|
||||
//
|
||||
|
||||
// SPI Interface
|
||||
static spi_device_handle_t spi;
|
||||
static spi_transaction_t lep_spi_trans;
|
||||
|
||||
// Pointer to allocated array to store one Lepton packet (DMA capable)
|
||||
static uint8_t* lepPacketP;
|
||||
|
||||
// Lepton Frame buffer (16-bit values)
|
||||
static uint16_t lepBuffer[LEP_NUM_PIXELS];
|
||||
|
||||
// Lepton Telemetry buffer (16-bit values)
|
||||
static uint16_t lepTelem[LEP_TEL_WORDS];
|
||||
|
||||
// Processing State
|
||||
static int curSegment = 1;
|
||||
static int curLinesPerSeg = LEP_NOTEL_PKTS_PER_SEG;
|
||||
static int curWordsPerSeg = LEP_NOTEL_WORDS_PER_SEG;
|
||||
static bool validSegmentRegion = false;
|
||||
static bool includeTelemetry = false;
|
||||
|
||||
|
||||
|
||||
|
||||
//
|
||||
// VoSPI Forward Declarations for internal functions
|
||||
//
|
||||
static bool transfer_packet(uint8_t* line, uint8_t* seg);
|
||||
static void copy_packet_to_lepton_buffer(uint8_t line);
|
||||
static void copy_packet_to_telem_buffer(uint8_t line);
|
||||
|
||||
|
||||
|
||||
//
|
||||
// VoSPI API
|
||||
//
|
||||
|
||||
/**
|
||||
* Initialise the VoSPI interface.
|
||||
*/
|
||||
int vospi_init()
|
||||
{
|
||||
esp_err_t ret;
|
||||
|
||||
spi_device_interface_config_t devcfg = {
|
||||
.command_bits = 0,
|
||||
.address_bits = 0,
|
||||
.mode = 3,
|
||||
.cs_ena_pretrans = 10,
|
||||
.clock_speed_hz = LEP_SPI_FREQ_HZ,
|
||||
.spics_io_num = LEP_CSN_PIN,
|
||||
.flags = SPI_DEVICE_HALFDUPLEX,
|
||||
.queue_size = 1
|
||||
};
|
||||
|
||||
if ((ret=spi_bus_add_device(LEP_SPI_HOST, &devcfg, &spi)) != ESP_OK) {
|
||||
printf("[VOSPI] Error: failed to add lepton spi device\n");
|
||||
} else {
|
||||
// Allocate DMA capable memory for the lepton packet
|
||||
lepPacketP = (uint8_t*) heap_caps_malloc(LEP_PKT_LENGTH, MALLOC_CAP_DMA);
|
||||
if (lepPacketP != NULL) {
|
||||
ret = ESP_OK;
|
||||
} else {
|
||||
printf("[VOSPI] Error: failed to allocate lepton DMA packet buffer\n");
|
||||
ret = ESP_FAIL;
|
||||
}
|
||||
}
|
||||
|
||||
// Setup our SPI transaction
|
||||
memset(&lep_spi_trans, 0, sizeof(spi_transaction_t));
|
||||
lep_spi_trans.tx_buffer = NULL;
|
||||
lep_spi_trans.rx_buffer = lepPacketP;
|
||||
lep_spi_trans.rxlength = LEP_PKT_LENGTH*8;
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Attempt to read a complete segment from the Lepton
|
||||
* - Data loaded into lepBuffer
|
||||
* - Returns true when last successful segment read, false otherwise
|
||||
*/
|
||||
bool vospi_transfer_segment(uint64_t vsyncDetectedUsec)
|
||||
{
|
||||
uint8_t line, prevLine;
|
||||
uint8_t segment;
|
||||
bool done = false;
|
||||
bool beforeValidData = true;
|
||||
bool success = false;
|
||||
|
||||
prevLine = 255;
|
||||
|
||||
while (!done) {
|
||||
if (transfer_packet(&line, &segment)) {
|
||||
// Saw a valid packet
|
||||
if (line == prevLine) {
|
||||
// This is garbage data since line numbers should always increment
|
||||
done = true;
|
||||
} else {
|
||||
// Check for termination or completion conditions
|
||||
if (line == 20) {
|
||||
// Check segment
|
||||
if (!validSegmentRegion) {
|
||||
// Look for start of valid segment data
|
||||
if (segment == 1) {
|
||||
beforeValidData = false;
|
||||
validSegmentRegion = true;
|
||||
}
|
||||
} else if ((segment < 2) || (segment > 4)) {
|
||||
// Hold/Reset in starting position (always collecting in segment 1 buffer locations)
|
||||
validSegmentRegion = false; // In case it was set
|
||||
curSegment = 1;
|
||||
}
|
||||
}
|
||||
|
||||
// Copy the data to the lepton frame buffer or telemetry buffer
|
||||
// - beforeValidData is used to collect data before we know if the current segment (1) is valid
|
||||
// - then we use validSegmentRegion for remaining data once we know we're seeing valid data
|
||||
if (includeTelemetry && validSegmentRegion && (curSegment == 4) && (line >= 57)) {
|
||||
copy_packet_to_telem_buffer(line - 57);
|
||||
}
|
||||
else if ((beforeValidData || validSegmentRegion) && (line < curLinesPerSeg)) {
|
||||
copy_packet_to_lepton_buffer(line);
|
||||
}
|
||||
|
||||
if (line == (curLinesPerSeg-1)) {
|
||||
// Saw a complete segment, move to next segment or complete frame aquisition if possible
|
||||
if (validSegmentRegion) {
|
||||
if (curSegment < 4) {
|
||||
// Setup to get next segment
|
||||
curSegment++;
|
||||
} else {
|
||||
// Got frame
|
||||
success = true;
|
||||
|
||||
// Setup to get the next frame
|
||||
curSegment = 1;
|
||||
validSegmentRegion = false;
|
||||
}
|
||||
}
|
||||
done = true;
|
||||
}
|
||||
}
|
||||
prevLine = line;
|
||||
} else if ((esp_timer_get_time() - vsyncDetectedUsec) > LEP_MAX_FRAME_XFER_WAIT_USEC) {
|
||||
// Did not see a valid packet within this segment interval
|
||||
done = true;
|
||||
}
|
||||
}
|
||||
|
||||
return success;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Load the a system buffer from our buffers for another task
|
||||
*/
|
||||
void vospi_get_frame(lep_buffer_t* sys_bufP)
|
||||
{
|
||||
uint16_t* sptr = sys_bufP->lep_bufferP;
|
||||
uint16_t* lptr = &lepBuffer[0];
|
||||
uint16_t min = 0xFFFF;
|
||||
uint16_t max = 0x0000;
|
||||
uint16_t t16;
|
||||
|
||||
// Load lepton image data
|
||||
while (lptr < &lepBuffer[LEP_NUM_PIXELS]) {
|
||||
t16 = *lptr++;
|
||||
if (t16 < min) min = t16;
|
||||
if (t16 > max) max = t16;
|
||||
*sptr++ = t16;
|
||||
}
|
||||
sys_bufP->lep_min_val = min;
|
||||
sys_bufP->lep_max_val = max;
|
||||
|
||||
// Optionally load telemetry
|
||||
sys_bufP->telem_valid = includeTelemetry;
|
||||
if (includeTelemetry) {
|
||||
sptr = sys_bufP->lep_telemP;
|
||||
lptr = &lepTelem[0];
|
||||
while (lptr < &lepTelem[LEP_TEL_WORDS]) {
|
||||
*sptr++ = *lptr++;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Configure the pipeline to include telemetry or not.
|
||||
* This should be done during initialization
|
||||
*/
|
||||
void vospi_include_telem(bool en)
|
||||
{
|
||||
includeTelemetry = en;
|
||||
curLinesPerSeg = (en) ? LEP_TEL_PKTS_PER_SEG : LEP_NOTEL_PKTS_PER_SEG;
|
||||
curWordsPerSeg = (en) ? LEP_TEL_WORDS_PER_SEG : LEP_NOTEL_WORDS_PER_SEG;
|
||||
}
|
||||
|
||||
|
||||
|
||||
//
|
||||
// VoSPI Forward Declarations for internal functions
|
||||
//
|
||||
|
||||
/**
|
||||
* Attempt to read one packet from the lepton
|
||||
* - Return false for discard packets
|
||||
* - Return true otherwise
|
||||
* - line contains the packet line number for all valid packets
|
||||
* - seg contains the packet segment number if the line number is 20
|
||||
*/
|
||||
static bool transfer_packet(uint8_t* line, uint8_t* seg)
|
||||
{
|
||||
bool valid = false;
|
||||
esp_err_t ret;
|
||||
|
||||
// *seg will be set if possible
|
||||
*seg = 0;
|
||||
|
||||
// Get a packet
|
||||
ret = spi_device_polling_transmit(spi, &lep_spi_trans);
|
||||
//ret = spi_device_transmit(spi, &lep_spi_trans);
|
||||
ESP_ERROR_CHECK(ret);
|
||||
|
||||
// Repeat as long as the frame is not valid, equals sync
|
||||
if ((*lepPacketP & 0x0F) == 0x0F) {
|
||||
valid = false;
|
||||
} else {
|
||||
*line = *(lepPacketP + 1);
|
||||
|
||||
// Get segment when possible
|
||||
if (*line == 20) {
|
||||
*seg = (*lepPacketP >> 4);
|
||||
}
|
||||
|
||||
valid = true;
|
||||
}
|
||||
|
||||
return(valid);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Copy the lepton packet to the raw lepton frame
|
||||
* - line specifies packet line number
|
||||
*/
|
||||
static void copy_packet_to_lepton_buffer(uint8_t line)
|
||||
{
|
||||
uint8_t* lepPopPtr = lepPacketP + 4;
|
||||
uint16_t* acqPushPtr = &lepBuffer[((curSegment-1) * curWordsPerSeg) + (line * (LEP_WIDTH/2))];
|
||||
uint16_t t;
|
||||
|
||||
while (lepPopPtr <= (lepPacketP + (LEP_PKT_LENGTH-1))) {
|
||||
t = *lepPopPtr++ << 8;
|
||||
t |= *lepPopPtr++;
|
||||
*acqPushPtr++ = t;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Copy the lepton packet to the telemetry buffer
|
||||
* - line specifies packet line number (only 0-2 are valid, do not call with line 3)
|
||||
*/
|
||||
static void copy_packet_to_telem_buffer(uint8_t line)
|
||||
{
|
||||
uint8_t* lepPopPtr = lepPacketP + 4;
|
||||
uint16_t* telPushPtr = &lepTelem[line * (LEP_WIDTH/2)];
|
||||
uint16_t t;
|
||||
|
||||
if (line > 2) return;
|
||||
|
||||
while (lepPopPtr <= (lepPacketP + (LEP_PKT_LENGTH-1))) {
|
||||
t = *lepPopPtr++ << 8;
|
||||
t |= *lepPopPtr++;
|
||||
*telPushPtr++ = t;
|
||||
}
|
||||
}
|
||||
|
||||
|
74
src/lipton/vospi.h
Normal file
74
src/lipton/vospi.h
Normal file
@@ -0,0 +1,74 @@
|
||||
/*
|
||||
* Lepton VoSPI Module
|
||||
*
|
||||
* Contains the functions to get frames from a Lepton 3.5 via its SPI port.
|
||||
* Optionally supports collecting telemetry when enabled as a footer (does not
|
||||
* support telemetry enabled as a header).
|
||||
*
|
||||
* Copyright 2020-2022 Dan Julio
|
||||
*
|
||||
* This file is part of tCam.
|
||||
*
|
||||
* tCam is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* tCam is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with tCam. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include "lepton_system.h"
|
||||
|
||||
|
||||
//
|
||||
// VoSPI Constants
|
||||
//
|
||||
|
||||
// LEP_FRAME_USEC is the per-frame period from the Lepton (interrupt rate)
|
||||
#define LEP_FRAME_USEC 9450
|
||||
// LEP_MAX_FRAME_XFER_WAIT_USEC specifies the maximum time we should wait in
|
||||
// vospi_transfer_segment() to read a valid frame. It should be LEP_FRAME_USEC -
|
||||
// (maximum ISR latency + transfer_packet() code path overhead)
|
||||
// than LEP_FRAME_USEC - maximum ISR latency)
|
||||
#define LEP_MAX_FRAME_XFER_WAIT_USEC 9250
|
||||
|
||||
#define LEP_WIDTH 160
|
||||
#define LEP_HEIGHT 120
|
||||
#define LEP_NUM_PIXELS (LEP_WIDTH * LEP_HEIGHT)
|
||||
#define LEP_PKT_LENGTH 164
|
||||
|
||||
// Telemetry related
|
||||
#define LEP_TEL_PACKETS 3
|
||||
#define LEP_TEL_PKT_LEN (LEP_PKT_LENGTH - 4)
|
||||
#define LEP_TEL_WORDS (LEP_TEL_PACKETS * LEP_TEL_PKT_LEN / 2)
|
||||
|
||||
// Dynamic values depending if telemetry is included or not
|
||||
#define LEP_TEL_PKTS_PER_SEG 61
|
||||
#define LEP_NOTEL_PKTS_PER_SEG 60
|
||||
#define LEP_TEL_WORDS_PER_SEG (LEP_TEL_PKTS_PER_SEG * LEP_WIDTH / 2)
|
||||
#define LEP_NOTEL_WORDS_PER_SEG (LEP_NOTEL_PKTS_PER_SEG * LEP_WIDTH / 2)
|
||||
|
||||
/* Lepton frame error return */
|
||||
enum LeptonReadError {
|
||||
NONE, DISCARD, SEGMENT_ERROR, ROW_ERROR, SEGMENT_INVALID
|
||||
};
|
||||
|
||||
|
||||
|
||||
//
|
||||
// VoSPI API
|
||||
//
|
||||
int vospi_init();
|
||||
bool vospi_transfer_segment(uint64_t vsyncDetectedUsec);
|
||||
void vospi_get_frame(lep_buffer_t* sys_bufP);
|
||||
void vospi_include_telem(bool en);
|
Reference in New Issue
Block a user