Browse Source

Code verändert, läuft noch nicht

master
Johannes Krug 5 years ago
parent
commit
8e04a74abc

arduino/Arduino_ESP32_MLX90640/Arduino_ESP32_MLX90640.ino → arduino/Arduino_ESP32_MLX90640_alt/Arduino_ESP32_MLX90640.ino View File

@@ -30,7 +30,7 @@ float T_max, T_min; // maximale bzw. minimale gemesse
float T_center; // Temperatur in der Bildschirmmitte


boolean isConnected();

// ***************************************
// **************** SETUP ****************

BIN
arduino/wärmebildkamera/Arduino_ESP32_MLX90640/MLX90640_I2C_Driver.zip View File


+ 313
- 0
arduino/wärmebildkamera/Arduino_ESP32_MLX90640_aktuell/Arduino_ESP32_MLX90640_aktuell.ino View File

@@ -0,0 +1,313 @@
#include <Wire.h>
#include "MLX90640_API.h"
#include "MLX90640_I2C_Driver1.h"
#include "SPI.h"
//#include "Adafruit_GFX.h"
//#include "Adafruit_ILI9341.h"

// For the ESP-WROVER_KIT, these are the default.
/*#define TFT_CS 15
#define TFT_DC 2
#define TFT_MOSI 13
#define TFT_CLK 14
#define TFT_RST 26
#define TFT_MISO 12
#define TFT_LED 27*/

/*Adafruit_ILI9341 tft = Adafruit_ILI9341(TFT_CS, TFT_DC, TFT_MOSI, TFT_CLK, TFT_RST, TFT_MISO);*/

const byte MLX90640_address = 0x33; //Default 7-bit unshifted address of the MLX90640

#define TA_SHIFT 8 //Default shift for MLX90640 in open air

static float mlx90640To[768];
paramsMLX90640 mlx90640;

int xPos, yPos; // Abtastposition
int R_colour, G_colour, B_colour; // RGB-Farbwert
int i, j; // Zählvariable
float T_max, T_min; // maximale bzw. minimale gemessene Temperatur
float T_center; // Temperatur in der Bildschirmmitte




// ***************************************
// **************** SETUP ****************
// ***************************************

void setup()
{
Serial.begin(115200);
Wire.begin();
Wire.setClock(400000); //Increase I2C clock speed to 400kHz

while (!Serial); //Wait for user to open terminal
Serial.println("MLX90640 IR Array Example");

if (isConnected() == false)
{
Serial.println("MLX90640 not detected at default I2C address. Please check wiring. Freezing.");
while (1);
}
Serial.println("MLX90640 online!");

//Get device parameters - We only have to do this once
int status;
uint16_t eeMLX90640[832];
status = MLX90640_DumpEE(MLX90640_address, eeMLX90640);
if (status != 0)
Serial.println("Failed to load system parameters");
if (status == 0)
Serial.println("dumpee_okay");

status = MLX90640_ExtractParameters(eeMLX90640, &mlx90640);
if (status != 0)
{
Serial.println("Parameter extraction failed");
Serial.print(" status = ");
Serial.println(status);
}

//Once params are extracted, we can release eeMLX90640 array

MLX90640_I2CWrite(0x33, 0x800D, 6401); // writes the value 1901 (HEX) = 6401 (DEC) in the register at position 0x800D to enable reading out the temperatures!!!
// ===============================================================================================================================================================

//MLX90640_SetRefreshRate(MLX90640_address, 0x00); //Set rate to 0.25Hz effective - Works
//MLX90640_SetRefreshRate(MLX90640_address, 0x01); //Set rate to 0.5Hz effective - Works
//MLX90640_SetRefreshRate(MLX90640_address, 0x02); //Set rate to 1Hz effective - Works
//MLX90640_SetRefreshRate(MLX90640_address, 0x03); //Set rate to 2Hz effective - Works
MLX90640_SetRefreshRate(MLX90640_address, 0x04); //Set rate to 4Hz effective - Works
//MLX90640_SetRefreshRate(MLX90640_address, 0x05); //Set rate to 8Hz effective - Works at 800kHz
//MLX90640_SetRefreshRate(MLX90640_address, 0x06); //Set rate to 16Hz effective - Works at 800kHz
//MLX90640_SetRefreshRate(MLX90640_address, 0x07); //Set rate to 32Hz effective - fails

//pinMode(TFT_LED, OUTPUT);
//digitalWrite(TFT_LED, HIGH);

/*tft.begin();

tft.setRotation(1);

tft.fillScreen(ILI9341_BLACK);
tft.fillRect(0, 0, 319, 13, tft.color565(255, 0, 10));
tft.setCursor(100, 3);
tft.setTextSize(1);
tft.setTextColor(ILI9341_YELLOW, tft.color565(255, 0, 10));
tft.print("Thermographie - stoppi");

tft.drawLine(250, 210 - 0, 258, 210 - 0, tft.color565(255, 255, 255));
tft.drawLine(250, 210 - 30, 258, 210 - 30, tft.color565(255, 255, 255));
tft.drawLine(250, 210 - 60, 258, 210 - 60, tft.color565(255, 255, 255));
tft.drawLine(250, 210 - 90, 258, 210 - 90, tft.color565(255, 255, 255));
tft.drawLine(250, 210 - 120, 258, 210 - 120, tft.color565(255, 255, 255));
tft.drawLine(250, 210 - 150, 258, 210 - 150, tft.color565(255, 255, 255));
tft.drawLine(250, 210 - 180, 258, 210 - 180, tft.color565(255, 255, 255));

tft.setCursor(80, 220);
tft.setTextColor(ILI9341_WHITE, tft.color565(0, 0, 0));
tft.print("T+ = ");


// drawing the colour-scale
// ========================
for (i = 0; i < 181; i++)
{
//value = random(180);
getColour(i);
tft.drawLine(240, 210 - i, 250, 210 - i, tft.color565(R_colour, G_colour, B_colour));
}


*/
}
// **********************************
// ************** LOOP **************
// **********************************

void loop(){
for (byte x = 0 ; x < 2 ; x++) //Read both subpages
{
uint16_t mlx90640Frame[834];
int status = MLX90640_GetFrameData(MLX90640_address, mlx90640Frame);
if (status < 0)
{
Serial.print("GetFrame Error: ");
Serial.println(status);
}

float vdd = MLX90640_GetVdd(mlx90640Frame, &mlx90640);
float Ta = MLX90640_GetTa(mlx90640Frame, &mlx90640);

float tr = Ta - TA_SHIFT; //Reflected temperature based on the sensor ambient temperature
float emissivity = 0.95;

MLX90640_CalculateTo(mlx90640Frame, &mlx90640, emissivity, tr, mlx90640To);
}

// determine T_min and T_max and eliminate error pixels
// ====================================================

mlx90640To[1*32 + 21] = 0.5 * (mlx90640To[1*32 + 20] + mlx90640To[1*32 + 22]); // eliminate the error-pixels
mlx90640To[4*32 + 30] = 0.5 * (mlx90640To[4*32 + 29] + mlx90640To[4*32 + 31]); // eliminate the error-pixels
T_min = mlx90640To[0];
T_max = mlx90640To[0];

for (i = 1; i < 768; i++)
{
if((mlx90640To[i] > -41) && (mlx90640To[i] < 301))
{
if(mlx90640To[i] < T_min)
{
T_min = mlx90640To[i];
}

if(mlx90640To[i] > T_max)
{
T_max = mlx90640To[i];
}
}
else if(i > 0) // temperature out of range
{
mlx90640To[i] = mlx90640To[i-1];
}
else
{
mlx90640To[i] = mlx90640To[i+1];
}
}


// determine T_center
// ==================

T_center = mlx90640To[11* 32 + 15];

// drawing the picture
// ===================

for (i = 0 ; i < 24 ; i++)
{
for (j = 0; j < 32; j++)
{
mlx90640To[i*32 + j] = 180.0 * (mlx90640To[i*32 + j] - T_min) / (T_max - T_min);
getColour(mlx90640To[i*32 + j]);
// tft.fillRect(217 - j * 7, 35 + i * 7, 7, 7, tft.color565(R_colour, G_colour, B_colour));
}
}
/*
tft.drawLine(217 - 15*7 + 3.5 - 5, 11*7 + 35 + 3.5, 217 - 15*7 + 3.5 + 5, 11*7 + 35 + 3.5, tft.color565(255, 255, 255));
tft.drawLine(217 - 15*7 + 3.5, 11*7 + 35 + 3.5 - 5, 217 - 15*7 + 3.5, 11*7 + 35 + 3.5 + 5, tft.color565(255, 255, 255));
tft.fillRect(260, 25, 37, 10, tft.color565(0, 0, 0));
tft.fillRect(260, 205, 37, 10, tft.color565(0, 0, 0));
tft.fillRect(115, 220, 37, 10, tft.color565(0, 0, 0));

tft.setTextColor(ILI9341_WHITE, tft.color565(0, 0, 0));
tft.setCursor(265, 25);
tft.print(T_max, 1);
tft.setCursor(265, 205);
tft.print(T_min, 1);
tft.setCursor(120, 220);
tft.print(T_center, 1);

tft.setCursor(300, 25);
tft.print("C");
tft.setCursor(300, 205);
tft.print("C");
tft.setCursor(155, 220);
tft.print("C");
*/
delay(20);
}


// ===============================
// ===== determine the colour ====
// ===============================

void getColour(int j)
{
if (j >= 0 && j < 30)
{
R_colour = 0;
G_colour = 0;
B_colour = 20 + (120.0/30.0) * j;
}
if (j >= 30 && j < 60)
{
R_colour = (120.0 / 30) * (j - 30.0);
G_colour = 0;
B_colour = 140 - (60.0/30.0) * (j - 30.0);
}

if (j >= 60 && j < 90)
{
R_colour = 120 + (135.0/30.0) * (j - 60.0);
G_colour = 0;
B_colour = 80 - (70.0/30.0) * (j - 60.0);
}

if (j >= 90 && j < 120)
{
R_colour = 255;
G_colour = 0 + (60.0/30.0) * (j - 90.0);
B_colour = 10 - (10.0/30.0) * (j - 90.0);
}

if (j >= 120 && j < 150)
{
R_colour = 255;
G_colour = 60 + (175.0/30.0) * (j - 120.0);
B_colour = 0;
}

if (j >= 150 && j <= 180)
{
R_colour = 255;
G_colour = 235 + (20.0/30.0) * (j - 150.0);
B_colour = 0 + 255.0/30.0 * (j - 150.0);
}

}
//Returns true if the MLX90640 is detected on the I2C bus
boolean isConnected()
{
Wire.beginTransmission((uint8_t)MLX90640_address);
if (Wire.endTransmission() != 0)
return (false); //Sensor did not ACK
return (true);
}

arduino/wärmebildkamera/Arduino_ESP32_MLX90640/MLX90640_API.zip → arduino/wärmebildkamera/Arduino_ESP32_MLX90640_aktuell/MLX90640_API.zip View File


+ 125
- 0
arduino/wärmebildkamera/Arduino_ESP32_MLX90640_aktuell/MLX90640_I2C_Driver1.cpp View File

@@ -0,0 +1,125 @@
/**
@copyright (C) 2017 Melexis N.V.

Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at

http://www.apache.org/licenses/LICENSE-2.0

Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.

*/

#include <Arduino.h>
#include <Wire.h>
#include "MLX90640_I2C_Driver.h"

void MLX90640_I2CInit()
{

}
int MLX90640_I2CRead(uint8_t _deviceAddress, unsigned int startAddress, unsigned int nWordsRead, uint16_t *data)
{
// nWordsRead must be <= 32767
Wire.beginTransmission(_deviceAddress);
Wire.write(startAddress >> 8); //MSB
Wire.write(startAddress & 0xFF); //LSB
Wire.endTransmission(false);
i2c_err_t error = Wire.readTransmission(_deviceAddress, (uint8_t*) data, nWordsRead*2);
if(error != 0){//problems
Serial.printf("Block read from sensor(0x%02X) at address=%d of %d uint16_t's failed=%d(%s)\n",
_deviceAddress,startAddress,nWordsRead,error,Wire.getErrorText(error));
}
else { // reverse byte order, sensor Big Endian, ESP32 Little Endian
for(auto a = 0; a<nWordsRead; a++){
data[a] = ((data[a] & 0xff)<<8) | (( data[a]>>8)&0xff);
}
}
return 0;
}
/*
//Read a number of words from startAddress. Store into Data array.
//Returns 0 if successful, -1 if error
int MLX90640_I2CRead(uint8_t _deviceAddress, unsigned int startAddress, unsigned int nWordsRead, uint16_t *data)
{

//Caller passes number of 'unsigned ints to read', increase this to 'bytes to read'
uint16_t bytesRemaining = nWordsRead * 2;

//It doesn't look like sequential read works. Do we need to re-issue the address command each time?

uint16_t dataSpot = 0; //Start at beginning of array

//Setup a series of chunked I2C_BUFFER_LENGTH byte reads
while (bytesRemaining > 0)
{
Wire.beginTransmission(_deviceAddress);
Wire.write(startAddress >> 8); //MSB
Wire.write(startAddress & 0xFF); //LSB
if(Wire.endTransmission(false) != 7){
Serial.println("Error: Sensor did not ack");
return (0);//Sensor did not ACK

}
uint16_t numberOfBytesToRead = bytesRemaining;
if (numberOfBytesToRead > I2C_BUFFER_LENGTH) numberOfBytesToRead = I2C_BUFFER_LENGTH;

Wire.requestFrom((uint8_t)_deviceAddress, numberOfBytesToRead);
if (Wire.available())
{
for (uint16_t x = 0 ; x < numberOfBytesToRead / 2; x++)
{
//Store data into array
data[dataSpot] = Wire.read() << 8; //MSB
data[dataSpot] |= Wire.read(); //LSB

dataSpot++;
}
}

bytesRemaining -= numberOfBytesToRead;

startAddress += numberOfBytesToRead / 2;
}

return (0); //Success
}
*/
//Set I2C Freq, in kHz
//MLX90640_I2CFreqSet(1000) sets frequency to 1MHz
void MLX90640_I2CFreqSet(int freq)
{
//i2c.frequency(1000 * freq);
Wire.setClock((long)1000 * freq);
}

//Write two bytes to a two byte address
int MLX90640_I2CWrite(uint8_t _deviceAddress, unsigned int writeAddress, uint16_t data)
{
Wire.beginTransmission((uint8_t)_deviceAddress);
Wire.write(writeAddress >> 8); //MSB
Wire.write(writeAddress & 0xFF); //LSB
Wire.write(data >> 8); //MSB
Wire.write(data & 0xFF); //LSB
if (Wire.endTransmission() != 0)
{
//Sensor did not ACK
Serial.println("Error: Sensor did not ack");
return (0);//Sensor did not ACK
}

uint16_t dataCheck;
MLX90640_I2CRead(_deviceAddress, writeAddress, 1, &dataCheck);
if (dataCheck != data)
{
//Serial.println("The write request didn't stick");
return -2;
}

return (0); //Success
}

+ 51
- 0
arduino/wärmebildkamera/Arduino_ESP32_MLX90640_aktuell/MLX90640_I2C_Driver1.h View File

@@ -0,0 +1,51 @@
/**
@copyright (C) 2017 Melexis N.V.

Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at

http://www.apache.org/licenses/LICENSE-2.0

Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.

*/
#ifndef _MLX90640_I2C_Driver_H_
#define _MLX90640_I2C_Driver_H_

#include <stdint.h>

//Define the size of the I2C buffer based on the platform the user has
//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__)

//I2C_BUFFER_LENGTH is defined in Wire.H
#define I2C_BUFFER_LENGTH BUFFER_LENGTH

#elif defined(__SAMD21G18A__)

//SAMD21 uses RingBuffer.h
#define I2C_BUFFER_LENGTH SERIAL_BUFFER_SIZE

#elif __MK20DX256__
//Teensy 3.2
#define I2C_BUFFER_LENGTH 32

#else

//The catch-all default is 32
#define I2C_BUFFER_LENGTH 32

#endif
//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=


void MLX90640_I2CInit(void);
int MLX90640_I2CRead(uint8_t slaveAddr, unsigned int startAddress, unsigned int nWordsRead, uint16_t *data);
int MLX90640_I2CWrite(uint8_t slaveAddr, unsigned int writeAddress, uint16_t data);
void MLX90640_I2CFreqSet(int freq);
#endif

+ 4
- 4
arduino/wärmebildkamera/Example1_BasicReadings/Example1_BasicReadings.ino View File

@@ -28,7 +28,6 @@
*/

#include <Wire.h>

#include "MLX90640_API.h"
#include "MLX90640_I2C_Driver.h"

@@ -86,10 +85,10 @@ void loop()

float tr = Ta - TA_SHIFT; //Reflected temperature based on the sensor ambient temperature
float emissivity = 0.95;
Serial.print("loop-schleife");
MLX90640_CalculateTo(mlx90640Frame, &mlx90640, emissivity, tr, mlx90640To);
}
Serial.print("loop-schleife2");
for (int x = 0 ; x < 10 ; x++)
{
Serial.print("Pixel ");
@@ -110,4 +109,5 @@ boolean isConnected()
if (Wire.endTransmission() != 0)
return (false); //Sensor did not ACK
return (true);
}
Serial.print("verbunden");
}

+ 27
- 4
arduino/wärmebildkamera/MLX90640_I2C_Driver.cpp View File

@@ -23,7 +23,26 @@ void MLX90640_I2CInit()
{

}

int MLX90640_I2CRead(uint8_t _deviceAddress, unsigned int startAddress, unsigned int nWordsRead, uint16_t *data)
{
// nWordsRead must be <= 32767
Wire.beginTransmission(_deviceAddress);
Wire.write(startAddress >> 8); //MSB
Wire.write(startAddress & 0xFF); //LSB
Wire.endTransmission(false);
i2c_err_t error = Wire.readTransmission(_deviceAddress, (uint8_t*) data, nWordsRead*2);
if(error != 0){//problems
Serial.printf("Block read from sensor(0x%02X) at address=%d of %d uint16_t's failed=%d(%s)\n",
_deviceAddress,startAddress,nWordsRead,error,Wire.getErrorText(error));
}
else { // reverse byte order, sensor Big Endian, ESP32 Little Endian
for(auto a = 0; a<nWordsRead; a++){
data[a] = ((data[a] & 0xff)<<8) | (( data[a]>>8)&0xff);
}
}
return 0;
}
/*
//Read a number of words from startAddress. Store into Data array.
//Returns 0 if successful, -1 if error
int MLX90640_I2CRead(uint8_t _deviceAddress, unsigned int startAddress, unsigned int nWordsRead, uint16_t *data)
@@ -42,7 +61,11 @@ int MLX90640_I2CRead(uint8_t _deviceAddress, unsigned int startAddress, unsigned
Wire.beginTransmission(_deviceAddress);
Wire.write(startAddress >> 8); //MSB
Wire.write(startAddress & 0xFF); //LSB
Wire.endTransmission(false)
if(Wire.endTransmission(false) != 7){
Serial.println("Error: Sensor did not ack");
return (0);//Sensor did not ACK

}
uint16_t numberOfBytesToRead = bytesRemaining;
if (numberOfBytesToRead > I2C_BUFFER_LENGTH) numberOfBytesToRead = I2C_BUFFER_LENGTH;

@@ -66,7 +89,7 @@ int MLX90640_I2CRead(uint8_t _deviceAddress, unsigned int startAddress, unsigned

return (0); //Success
}
*/
//Set I2C Freq, in kHz
//MLX90640_I2CFreqSet(1000) sets frequency to 1MHz
void MLX90640_I2CFreqSet(int freq)
@@ -87,7 +110,7 @@ int MLX90640_I2CWrite(uint8_t _deviceAddress, unsigned int writeAddress, uint16_
{
//Sensor did not ACK
Serial.println("Error: Sensor did not ack");
return (-1);
return (0);//Sensor did not ACK
}

uint16_t dataCheck;

Loading…
Cancel
Save